Re: Remote mapping Kinect2

Posted by matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Remote-mapping-Kinect2-tp2980p2999.html

Hi,

In your case, implementing a simple wheel odometry (e.g. encoders) approach on the robot would save a lot of computing resources.

For remote mapping, see this tutorial: Remote Mapping. Converting to Kinectv2 would look like this:

1- Launch kinectv2 on robot
$ roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true

2- Launch data throttling on robot
<launch>
  <arg name="rate"  default="5"/>
  <arg name="decimation"  default="1"/> <!-- Reduce the image size, e.g., 2 means "width/2 x height/2". -->
  <arg name="resolution" default="qhd" />
  <arg name="approx_sync" default="false" /> <!-- kinect2_bridge has synchronized images -->

  <!-- Use kinect2 nodelet manager -->
  <node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap_ros/data_throttle kinect2" output="screen">
      <param name="rate" type="double" value="$(arg rate)"/>
      <param name="decimation" type="int" value="$(arg decimation)"/>
      <param name="approx_sync" type="bool" value="$(arg approx_sync)"/>

      <remap from="rgb/image_in"       to="/kinect2/$(arg resolution)/image_color_rect"/>
      <remap from="depth/image_in"     to="/kinect2/$(arg resolution)/image_depth_rect"/>
      <remap from="rgb/camera_info_in" to="/kinect2/$(arg resolution)/camera_info"/>

      <remap from="rgb/image_out"       to="/kinect2/data_throttled_image"/>
      <remap from="depth/image_out"     to="/kinect2/data_throttled_image_depth"/>
      <remap from="rgb/camera_info_out" to="/kinect2/data_throttled_camera_info"/>
  </node>    
</launch>

3- Launch rtabmap on remote computer:
roslaunch rtabmap_ros rtabmap.launch \
   rgb_topic:=/kinect2/data_throttled_image \
   depth_topic:=/kinect2/data_throttled_image_depth \
   camera_info_topic:=/kinect2/data_throttled_camera_info \
   compressed:=true \
   approx_sync:=false \
   rtabmap_args:="--delete_db_on_start"

Note that both computers should be synchronized ("ntpdate" for example). Verify that input topics are received:
$ rostopic hz /kinect2/data_throttled_image
$ rostopic hz /kinect2/data_throttled_image_depth
$ rostopic hz /kinect2/data_throttled_camera_info

cheers,
Mathieu