Gazebo Classic OctoMap Models with ROS 1
The OctoMap library is an open source library for generating volumetric 3D environment models from sensor data. This model data can then be used by a drone for navigation and obstacle avoidance.
This guide covers how to use OctoMap with the Gazebo Classic Rotors Simulator and ROS.
Installation
The installation requires ROS, Gazebo Classic and the Rotors Simulator plugin. Follow the Rotors Simulator instructions to install.
Next, install the OctoMap library:
Now, open ~/catkin_ws/src/rotors_simulator/rotors_gazebo/CMakeLists.txt
and add the following lines to the bottom of the file:
Open ~/catkin_ws/src/rotors_simulator/rotors_gazebo/package.xml
and add the following lines:
Run the following two lines:
:::note The first line changes your default shell editor to gedit. This is recommended for users who have little experience with vim (the default editor), but can otherwise be omitted. :::
and change the two following lines:
to:
Running the Simulation
Run the following three lines in separate terminal windows. This opens up Gazebo Classic, Rviz and an octomap server.
In Rviz, change the field 'Fixed Frame' from 'map' to 'world' in the top left of the window. Now click the add button in the bottom left and select MarkerArray. Then double click the MarkerArray and change 'Marker Topic' from '/free_cells_vis_array' to '/occupied_cells_vis_array'
Now you should see a part of the floor.
In the Gazebo Classic window, insert a cube in front of the red rotors and you should see it in Rviz.
Last updated