ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

"No map recieved" in Rviz with RTABMap remote mapping

asked 2018-03-27 08:20:41 -0500

Dox gravatar image

updated 2018-04-06 16:36:04 -0500

Hello!

I'm trying to do 3D mapping and navigation with ROS using Raspberry Pi 3 and XBOX Kinect 360 camera on Pioneer robot and laptop as a workstation from where I will be able to visualize and send commands to RPi3. On my laptop, I am running Ubuntu 14.04 LTS 32-bit with ROS Kinetic, and on RPi3 Ubuntu Mate with ROS Kinetic also.

I had some success when launching RTABMap on RPi3, and using laptop for visualization only, but now I want to do it remotely, so for start I modified these two launch files:

https://github.com/introlab/rtabmap_r... https://github.com/introlab/rtabmap_r...

I'm providing the content of modified launch files below:

remote_robot.launch

    <launch>

    <arg name="rate"        default="25"/>
    <arg name="decimation"  default="1"/>
    <arg name="approx_sync" default="true"/>


<!--  PLATFORM SPECIFIC -->

   <!-- Base Controller -->
   <!-- Starting ROSARIA driver for motors and encoders -->
   <node pkg ="rosaria" type ="RosAria" name="RosAria">
    <param name="port" value="/dev/ttyUSB0" type="string"/>
   </node>
    <!-- Remapping -->
    <!--<remap from="/cmd_vel" to="/cmd_vel"/> -->
    <!--<remap from="/rosaria/cmd_vel" to="/cmd_vel" /> -->
    <!--<remap from="/rosaria/pose" to="/pose" /> -->


   <!-- RosAria client -->
   <!-- <include file="$(find rosaria_client)/launch/rosaria_client_launcher.launch" /> -->
   <!-- <node pkg="rosaria_client" type="interface" name="RosAria_interface" output="screen"/> -->

   <!-- TRANSFORMS -->
   <!-- static_transform_publisher x y z yaw pitch roll  frame_id   child_frame_id   period (ms) -->
   <node pkg="tf" type="static_transform_publisher" name="Pioneer3AT_tf" args="0.2 0.0 0.12 0 0 0 base_link camera_link 100" />


   <!-- SENSORS INFORMATION - Kinect driver, fakse scaner -->
   <!-- <include file="$(find pioneer_3at_nav)/myKinect.launch" /> -->
   <include file="$(find freenect_launch)/launch/freenect.launch">
      <arg name="depth_registration" value="true"/>
   </include>

  <!-- Fake laser -->
  <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan">
    <remap from="image"         to="/camera/depth_registered/image_raw"/>
    <remap from="camera_info"   to="/camera/depth_registered/camera_info"/>
    <!--<remap from="scan"      to="/scan"/>-->
    <param name="range_max" type="double" value="4"/>
  </node>   


  <!-- Throttling messages -->
  <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="5.0"/> -->
     <!-- <param name="approx_sync" type="bool" value="true"/> -->

      <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="/camera/rgb/image_rect_color"/>
      <remap from="depth/image_in"     to="/camera/depth_registered/image_raw"/>
      <remap from="rgb/camera_info_in" to="/camera/depth_registered/camera_info"/>

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


   <!-- SLAM is done on client side...-->
</launch>

remote_mapping_rviz.launch

<launch>
  <arg name="rtabmap_args" default="" />    

  <!-- Remote teleop - RosAria -->
  <node pkg="rosaria_client" type="teleop" name="RosAria_interface" output="screen"/>
    <group ns="teleop">
       <remap from="~cmd_vel" to="/cmd_vel"/>
        </group>

  <!-- Visualization and SLAM nodes use same data, so just subscribe once and relay messages -->
  <node name="mapData_relay" type="relay" pkg="topic_tools" args="/rtabmap/mapData /rtabmap/mapData_relay"/>
  <node name="odom_relay" type="relay" pkg="topic_tools" args="/odom /odom_relay"/>
  <node name="scan_relay" type="relay" pkg="topic_tools" args="/scan /scan_relay"/>
  <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 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-03-27 17:00:34 -0500

matlabbe gravatar image

The az3_* files use the old code and map_assembler is not required. I recommend to follow the Remote Mapping tutorial instead. To use robot odometry with this tutorial, the remote computer could launch:

$ roslaunch rtabmap_ros rtabmap.launch \
  rgb_topic:=/camera/data_throttled_image \
  depth_topic:=/camera/data_throttled_image_depth \
  camera_info_topic:=/camera/data_throttled_camera_info \
  compressed:=true \
  rtabmap_args:="--delete_db_on_start" \
  visual_odometry:=false \
  odom_topic:=/odom \
  queue_size:=10

While you are receiving all topics separately, lags on network and different frame rates can affect the ability to remote nodes (e.g., rtabmap) to correctly synchronize the topics. You may check the rate of the topics that rtabmap is subscribed to with rostopic hz. If some topics are at 50 Hz while other are at 3 Hz, rtabmap won't be able to synchronize them by default. The queue_size parameter should be increased (default 10). You can also throttle the topics on robot side so they are all published at the same rate (this can save network bandwidth at the same time).

cheers

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-03-27 08:20:41 -0500

Seen: 973 times

Last updated: Apr 06 '18