ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Hi,
If rtabmap node is on client side, you should throttle the subscribed compressed topics and use relays to avoid multiple subscriptions on the same topics used by rviz, rtabmap or rtabmapviz (the messages should only be sent one time over the network). See this example:
<node name="camera_info_relay" type="relay" pkg="topic_tools" args="/camera/data_throttled_camera_info /camera/data_throttled_camera_info_relay" />
<node name="republish_rgb" type="republish" pkg="image_transport" args="theora in:=/camera/data_throttled_image raw out:=/camera/data_throttled_image_relay" />
<node name="republish_depth" type="republish" pkg="image_transport" args="compressedDepth in:=/camera/data_throttled_image_depth raw out:=/camera/data_throttled_image_depth_relay" />
The throttled topics on the robot side can be created with data_throttle node. Example at the beginning of section 6 of this page:
<group ns="camera">
<node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap/data_throttle camera_nodelet_manager" output="screen">
<param name="rate" type="double" value="5.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>
cheers
2 | No.2 Revision |
Hi,
If rtabmap node is on client side, you should throttle the subscribed compressed topics and use relays to avoid multiple subscriptions on the same topics used by rviz, rtabmap or rtabmapviz (the messages should only be sent one time over the network). See this example:
<node name="camera_info_relay" type="relay" pkg="topic_tools" args="/camera/data_throttled_camera_info /camera/data_throttled_camera_info_relay" />
<node name="republish_rgb" type="republish" pkg="image_transport" args="theora in:=/camera/data_throttled_image raw out:=/camera/data_throttled_image_relay" />
<node name="republish_depth" type="republish" pkg="image_transport" args="compressedDepth in:=/camera/data_throttled_image_depth raw out:=/camera/data_throttled_image_depth_relay" />
The throttled topics on the robot side can be created with data_throttle node. Example at the beginning of section 6 of this page:
<launch>
<include file="$(find freenect_launch)/launch/freenect.launch">
<arg name="depth_registration" value="True" />
</include>
<!-- Use same nodelet used by Freenect/OpenNI -->
<group ns="camera">
<node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap/data_throttle camera_nodelet_manager" output="screen">
<param name="rate" type="double" value="5.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>
</group>
</launch>
cheers
3 | No.3 Revision |
Hi,
If rtabmap node is on client side, you should throttle the subscribed compressed topics and use relays to avoid multiple subscriptions on the same topics used by rviz, rtabmap or rtabmapviz (the messages should only be sent one time over the network). See this example:
<node name="camera_info_relay" type="relay" pkg="topic_tools" args="/camera/data_throttled_camera_info /camera/data_throttled_camera_info_relay" />
<node name="republish_rgb" type="republish" pkg="image_transport" args="theora in:=/camera/data_throttled_image raw out:=/camera/data_throttled_image_relay" />
<node name="republish_depth" type="republish" pkg="image_transport" args="compressedDepth in:=/camera/data_throttled_image_depth raw out:=/camera/data_throttled_image_depth_relay" />
The throttled topics on the robot side can be created with data_throttle node. Example at the beginning of section 6 of this page:
<launch>
<include file="$(find freenect_launch)/launch/freenect.launch">
<arg name="depth_registration" value="True" />
</include>
<!-- Use same nodelet used by Freenect/OpenNI -->
<group ns="camera">
<node pkg="nodelet" type="nodelet" name="data_throttle" args="load rtabmap/data_throttle rtabmap_ros/data_throttle camera_nodelet_manager" output="screen">
<param name="rate" type="double" value="5.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>
</launch>
EDIT
There is a new tutorial on remote mapping here: http://wiki.ros.org/rtabmap_ros/Tutorials/RemoteMapping
cheers