3D Perception/Configuration Tutorial

In this section, we will walk through configuring the 3D sensors on your robot with MoveIt!. The primary component in MoveIt! that deals with 3D perception is the Occupancy Map Updater. The updater uses a plugin architecture to process different types of input. The currently available plugins in MoveIt! are:
  • The PointCloud Occupany Map Updater: which can take as input point clouds (sensor_msgs/PointCloud2)
  • The Depth Image Occupancy Map Updater: which can take as input Depth Images (sensor_msgs/Image)

YAML Configuration file (Point Cloud)

We will have to generate a YAML configuration file for configuring the 3D sensors. An example file for processing point clouds can be found in the moveit_pr2 github project

sensors:
  - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
    point_cloud_topic: /head_mount_kinect/depth_registered/points
    max_range: 5.0
    point_subsample: 1
    padding_offset: 0.1
    padding_scale: 1.0
    filtered_cloud_topic: filtered_cloud
The general parameters are:
  • sensor_plugin: The name of the plugin that we are using.
Parameters specific to the Point cloud updater are:
  • point_cloud_topic: This specifies the topic to listen on for a point cloud.
  • max_range: (in m) Points further than this will not be used.
  • point_subsample: Choose one of every point_subsample points.
  • padding_offset: The size of the padding (in cm).
  • padding_scale:
  • filtered_cloud_topic: The topic on which the filtered cloud will be published (mainly for debugging). The filtering cloud is the resultant cloud after self-filtering has been performed.

YAML Configuration file (Depth Map)

We will have to generate a rgbd.yaml configuration file for configuring the 3D sensors. An example file for processing point clouds can be found in the moveit_advanced github project

sensors:
  - sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
    image_topic: /head_mount_kinect/depth_registered/image_raw
    queue_size: 5
    near_clipping_plane_distance: 0.3
    far_clipping_plane_distance: 5.0
    shadow_threshold: 0.2
    padding_scale: 4.0
    padding_offset: 0.03
    filtered_cloud_topic: filtered_cloud
The general parameters are:
  • sensor_plugin: The name of the plugin that we are using.
Parameters specific to the Depth Map updater are:
  • image_topic: This specifies the topic to listen on for a depth image.
  • queue_size: he number of images to queue up
  • near_clipping_plane_distance:
  • far_clipping_plane_distance:
  • shadow_threshold:
  • padding_offset: The size of the padding (in cm).
  • padding_scale:
  • filtered_cloud_topic: The topic on which the filtered cloud will be published (mainly for debugging). The filtering cloud is the resultant cloud after self-filtering has been performed.

Update the launch file

Add the YAML file to the launch script

You will now need to update the moveit_sensor_manager.launch file in the “launch” directory of your MoveIt! configuration directory with this sensor information (this file is auto-generated by the Setup Assistant but is empty). You will need to add the following line into that file to configure the set of sensor sources for MoveIt! to use:

<rosparam command="load" file="$(find my_moveit_config)/config/sensors_kinect.yaml" />

Note that you will need to input the path to the right file you have created above.

Octomap Configuration

You will also need to configure the Octomap by adding the following lines into the moveit_sensor_manager.launch:

<param name="octomap_frame" type="string" value="odom_combined" />
<param name="octomap_resolution" type="double" value="0.05" />
<param name="max_range" type="double" value="5.0" />
MoveIt! uses an octree based framework to represent the world around it. The Octomap parameters above are configuration parameters for this representation:
  • octomap_frame: specifies the coordinate frame in which this representation will be stored. If you are working with a mobile robot, this frame should be a fixed frame in the world.
  • octomap_resolution: specifies the resolution at which this representation is maintained (in meters).
  • max_range: specifies the maximum range value to be applied for any sensor input to this node.

Open Source Feedback

See something that needs improvement? Please open a pull request on this GitHub page