Simulation environment

The simulation environment for the OSMOSIS project is based on Gazebo, and uses simulation packages provided by the Summit XL (the robot platform) constructor, Robotnik. The source code of the simulation that is specific to OSMOSIS is available on https://gitlab.com/osmosis/osmosis_simulation.

The simulation environment contains a partial map of the Toulouse-Blagnac airport, and a 3D model of the Summit XL robot.

Installation

The following procedures is given for Ubuntu 18.04 and ROS Melodic. You must first follow the installation instructions of ROS.

Dependencies

To install the simulation environment, you need first to install ROS and Gazebo, and some common packages provided by Robotnik.

sudo apt install ros-melodic-ros-base python-vcstool \
  ros-melodic-gazebo-ros ros-melodic-gazebo-plugins \
  ros-melodic-costmap-2d ros-melodic-robot-localization \
  ros-melodic-mavros-msgs ros-melodic-gmapping \
  ros-melodic-navigation ros-melodic-xacro \
  ros-melodic-hector-gazebo-plugins \
  ros-melodic-teb-local-planner \
  ros-melodic-ros-controllers

Workspace

Then create a ROS workspace for the simulation, and clone the necessary repositories:

source /opt/ros/melodic/setup.bash
mkdir -p ~/osmosis_ws/src
cd ~/osmosis_ws/src
git clone https://gitlab.com/osmosis/osmosis_simulation
vcs import < osmosis_simulation/osmosis.repos
cd ..
catkin_make

Launch the simulation

cd ~/osmosis_ws
source devel/setup.bash
roslaunch osmosis_simulation summit_xl_simulation.launch

Controlling the robot

You can test the simulation by sending direct commands to the robot using ROS. For instance, in a terminal:

cd ~/osmosis_ws
source devel/setup.bash
rostopic pub /summit_xl_a/robotnik_base_control/cmd_vel geometry_msgs/Twist '[0.2, 0.0, 0.0]' '[0.0, 0.0, -0.1]'

You can also use one of the control architecture implementation provided by OSMOSIS.

Relevant topics

The relevant topics available in the simulation are :

  • '/summit_xl_a/robotnik_base_control/cmd_vel' (type geometry_msgs/Twist): to send commands to the robot
  • '/summit_xl_a/imu/data' (type sensor_msgs/Imu): to get IMU data
  • '/summit_xl_a/ground_truth/state' (type nav_msgs/Odometry): to get the true pose of the robot, or to use in place of the robot odometry (which is bugged in the simulation)
  • '/summit_xl_a/front_laser/scan' (type sensor_msgs/LaserScan): to get the laser scan
  • '/summit_xl_a/fix' (type sensor_msgs/NavSatFix): to get GPS fix

results matching ""

    No results matching ""