Note: This tutorial assumes that you have completed the previous tutorials: rc_visard/Tutorials/FirstSteps.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Create octomap using rc_visard's onboard SLAM

Description: This tutorial shows how to create an OctoMap using the pointclouds and SLAM trajectory of the rc_visard

Keywords: rc_visard, octomap, slam

Tutorial Level: BEGINNER

Next Tutorial: rc_visard/Tutorials/NavigationWithTurtlebot

Goal

This tutorial shows how to create an OctoMap using the pointclouds and the SLAM trajectory of the rc_visard - as demonstrated in the first half of the following "fruitful" video:

(If the video doesn't show up, click here)

Overview

To create a 3D voxel representation of the environment we explore the environment with the rc_visard while recording the pointclouds. The optional onboard SLAM module on the rc_visard is running during recording, so we can get the optimized trajectory afterwards. We then use this trajectory together with the recorded pointclouds to replay the bag file for generating an octomap.

The reason for not building the octomap "online" is that we can achieve a better quality/consisteny in the octomap if we build it afterwards when we already have the optimized trajectory (after loop closures). One could also build the octomap incrementally/online while exploring the environment, but then points/voxels only observed once will be at the initially observed position and won't benefit from the loop closures of the onboard SLAM.

To collect the data, one possibility is to mount the rc_visard on a TurtleBot and drive it around using Teleop.

While this is fun to do, it is not necessary to have a turtlebot for creating the map and you could also just carry around the rc_visard by hand or mount it on any other platform.

  Show EOL distros: 

Setup

Install dependencies

Make sure the rc_visard_driver has already been installed as explained in rc_visard/Tutorials/FirstSteps.

Download the tutorial repository into a catkin workspace:

 $ mkdir -p catkin_ws/src && git clone https://github.com/roboception/rc_visard_turtlebot_tutorial.git -b indigo catkin_ws/src/rc_visard_turtlebot_tutorial

You can then use rosdep to install missing dependencies (e.g., octomap_server) for this tutorial, i.e.

 $ rosdep init #for first time use of rosdep
 $ rosdep update
 $ rosdep install --from-paths catkin_ws/src/rc_visard_turtlebot_tutorial

If any dependencies are missing you may be prompted for your password to install the respective packages.

Download the tutorial repository into a catkin workspace:

 $ mkdir -p catkin_ws/src && git clone https://github.com/roboception/rc_visard_turtlebot_tutorial.git catkin_ws/src/rc_visard_turtlebot_tutorial

The turtlebot-package is no longer supported and needs to be installed from source.

Use the install_turtlebot.sh script found in the tutorial directory to clone the necessary packages into the src directory. To do this follow these steps:

1. Export the path to your catkin workspace:

 $ export ROS_WORKSPACE=$(pwd)/catkin_ws/src

$(pwd) prints the working directory.

2. Clone the necessary packages into your workspace using the install_turtlebot-script found in the rc_visard_turtlebot_tutorial:

 $ catkin_ws/src/rc_visard_turtlebot_tutorial/install_turtlebot.sh

3. Install the packages:

 $ catkin_make install -C catkin_ws

4. Source the workspace:

 $ source catkin_ws/devel/setup.bash

Step 4 has to be done for each new shell. To avoid this append the command with the the absolute filepath to your bashrc:

 $ echo "source </absolute/path/to/your/catkin_ws/devel/setup.bash>" >> ~/.bashrc

You can then use rosdep to install missing dependencies (e.g., octomap_server) for this tutorial, i.e.

 $ rosdep init #for first time use of rosdep
 $ rosdep update
 $ rosdep install --from-paths catkin_ws/src/rc_visard_turtlebot_tutorial

If any dependencies are missing you may be prompted for your password to install the respective packages.

Setup with ssh

This is not necessary but convenient to monitor and start your process on the Turtlebot. We use screen as a terminal multiplexer so that we don't need to establish a new SSH-connection for each new bash-screen. Each new screen is also in the working directory from which you started the screen session. Make sure to have added the source of your catkin workspace to your bashrc before starting your screen session. Otherwise you would need to source it for each and every screen:

 $ echo "source </absolute/path/to/your/catkin_ws/devel/setup.bash>" >> ~/.bashrc

If you haven't done so already at ROS to your .bashrc as well:

 $ echo "source /opt/ros/$ROS_DISTRO/setup.bash" >> ~/.bashrc

Setup of the Turtlebot

You can skip this part if you are not using the Turtlebot.

After sourcing your ROS set up the Turtlebot with a udev rule. If this is not set, the Turtlebot won't be connected at /dev/kobuki. Instead it will have a random name. (Remember to have a roscore running when you are trying to use rosrun):

 $ roscore &

 $ rosrun kobuki_ftdi create_udev_rules 

 $ fg

Now stop the roscore with CTRL-C.

You need to reattach the USB-connection to update /dev.

To start the Turtlebot:

 $ roslaunch rc_visard_turtlebot_tutorial turtlebot_driver.launch

This will print out an error message around every 20 seconds but this message can be ignored.

For teleoperation with the keyboard use this:

 $ roslaunch turtlebot_teleop keyboard_teleop.launch

If you are using teleoperation with a ps3-controller, launch it with:

 $ roslaunch rc_visard_turtlebot_tutorial ps3_teleop.launch

To move around keep the L1 Button depressed.

Execute

Start rc_visard_driver with trajectory publishing

In case only one rc_visard is connected to the network, start the rc_visard_driver as follows:

 $ rosrun rc_visard_driver rc_visard_driver _autostart_dynamics:=True _autostart_dynamics_with_slam:=True _autostop_dynamics:=True _autopublish_trajectory:=True _enable_tf:=True

If more than one rc_visard is connected in your network, use the serial number of your device. You can find the serial number using rcdiscover

 $ rcdiscover

 $ rosrun rc_visard_driver rc_visard_driver _device:=:<serial_number_of_your_device> _autostart_dynamics:=True _autostart_dynamics_with_slam:=True _autostop_dynamics:=True _autopublish_trajectory:=True _enable_tf:=True

Make sure you configure the rc_visard appropriately for the application. You can use dynamic_reconfigure for this, see also rc_visard_driver for parameters. For instance, settings for the Depth Image to consider are:

  • depth_maxdepth: Maximum depth. Don't set it too low, as the free information is valuable

  • depth_maxdeptherr: Maximum depth error. Don't set it too low, for the same reason, but also not too high, to avoid inaccuracies. For indoors 0.2-0.5 is good.

  • depth_minconf: Minimum confidence. Might be worth to increase, if you have problems with artifacts.

It's also a good idea to start RViz so you can see what the rc_visard is seeing. If you are using a SSH-connection use your hostmachine. To connect your hostmachine to the ROS-network on the Turtlebot use this:

 $ export ROS_MASTER_URI=http://<ip_address_of_your_turtlebot>:11311

For more information about ROS-variables see this.

Start rviz with the configuration-file provided by this tutorial. If you have it installed on the machine, where you are using rviz:

 $ rviz -d $(rospack find rc_visard_turtlebot_tutorial)/cfg/map_generation.rviz

If you have not installed the tutorial there:

 $ rviz -d <path/to/rc_visard_turtlebot_tutorial/cfg/map_generation.rviz>

Record bagfile with pointclouds

In this part we will create and store bagfiles for our map in a map directory:

 $ mkdir map

 $ rosbag record --lz4 -O map/clouds.bag /stereo/points2

Now move the rc_visard around and explore the environment. Make sure that you are not mapping moving objects like colleagues since they would be shown as obstacles in the octomap. When you are done, stop the rosbag record with CTRL-C.

Get trajectory from rc_visard and store onboard SLAM map

Use the save_trajectory_as_tf.py script from the tutorial repository to get the optimized trajectory from rc_visard and add the SLAM corrected tf transformations to the recorded pointclouds:

 $ rosrun rc_visard_turtlebot_tutorial save_trajectory_as_tf.py map/clouds.bag map/clouds_with_tf.bag

Stop the SLAM module on rc_visard and store the internal SLAM map.

 $ rosservice call /rc_visard_driver/dynamics_stop

 $ rosservice call /rc_visard_driver/slam_save_map

Stop the rc_visard_driver and the turtlebot now. To do this change into the windows, in which you started the turtlebot, the teleoperation, and the rc_visard_driver and terminate all of these with CTRL-C.

Generate octomap

Start the octomap_server with the launch file provided in the tutorial repository

 $ roslaunch rc_visard_turtlebot_tutorial octomap_mapping.launch

Playback the bagfile:

 $ rosbag play -r 1 map/clouds_with_tf.bag

Since you are playing back tf data, make sure no other transformations are sent out on /tf, e.g., from the rc_visard or the turtlebot drivers

You can adapt the playback rate depending on your CPU (if the octomap_server_node uses far less than 100% of one cpu core, you may increase the rate for faster processing, if it is close to 100% reduce it to make sure all point clouds are processed). Finally save the octomap when the playback of the bagfile is done:

 $ rosrun octomap_server octomap_saver -f map/mapfile.ot

Before starting the next tutorial go to the window, where you started the octomap_mapping.launch, and shut it down with CTRL-C.

What Next?

Wiki: rc_visard/Tutorials/CreateOctomapWithSLAM (last edited 2019-07-08 15:14:54 by JanNiklasBlind)