If images are streamed from another computer, I would suggest to add compressed:=true
to your line:
$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rviz:=true rtabmapviz:=false compressed:=true
Your remote computer will then subscribe to compressed image topics instead of the raw ones, saving a lot of network bandwidth.
You may also want to reduce the frame rate of your camera to ~10/15 Hz to save even more bandwidth, similar to this example. You could use rtabmap_ros/data_throttle nodelet on adroid to reduce the frame rate, if the driver used for the camera doesn't have the option. Here is an example loading the nodelet in the camera nodelet manager of your camera:
<group ns="camera">
<node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap_ros/data_throttle camera_nodelet_manager" output="screen">
<param name="rate" type="double" value="10.0"/>
<remap from="rgb/image_in" to="rgb/image_rect_color"/>
<remap from="depth/image_in" to="depth_registered/image_raw"/>
<remap from="rgb/camera_info_in" to="rgb/camera_info"/>
<remap from="rgb/image_out" to="data_throttled_image"/>
<remap from="depth/image_out" to="data_throttled_image_depth"/>
<remap from="rgb/camera_info_out" to="data_throttled_camera_info"/>
</node>
</group>
The line above would be modified with the correct topics:
$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rviz:=true rtabmapviz:=false compressed:=true rgb_topic:=/camera/data_throttled_image depth_registered_topic:=/camera/data_throttled_image_depth camera_info_topic:=/camera/data_throttled_camera_info
EDIT
For the first example, you can verify that you are correctly receiving the compressed topics on the laptop with:
$ rostopic hz /camera/rgb/image_rect_color/compressed
$ rostopic hz /camera/depth_registered/image_raw/compressedDepth
EDIT 2
Making sure that ROS_IP
is set on both computers (to avoid a computer not seeing topics of the other), it works if I do this (well openni2_launch can be used instead of freenect_launch):
A) computer A:
$ roslaunch freenect_launch freenect.launch depth_registration:=true
B) computer B:
$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rviz:=true rtabmapviz:=false compressed:=true
Make sure to uncheck Image display in RVIZ to avoid subscribing to raw image, which would results in 30 MB/sec bandwidth!! Removing the Image display or setting Transport hint
to "theora" instead of "raw", I have 3.5 MB/sec bandwidth. If I do the data_throttle
example with 10 Hz instead of 30 Hz framerate:
A) computer A:
$ roslaunch freenect_launch freenect.launch depth_registration:=true
$ roslaunch data_throttle.launch
B) computer B:
$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rviz:=true rtabmapviz:=false compressed:=true rgb_topic:=/camera/data_throttled_image depth_registered_topic:=/camera/data_throttled_image_depth camera_info_topic:=/camera/data_throttled_camera_info
With this setup, I have now 1 MB/sec bandwidth.

cheers