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

Errors using Rtabmap and also in running gmapping and Rtabmap simultaneously.

asked 2018-08-29 09:19:39 -0600

NAGALLA DEEPAK gravatar image

updated 2018-08-29 11:47:18 -0600

I have tried many methods suggested in Kinect + Odometry + 2D laser and changed odom and scan topics that suit my robot specifications. But, I could not get any data neither in RViz nor in Rtab GUI. and my launch file is rtabmap.launch.I am getting this error

    [ WARN] [1535559564.824509798]: /rtabmap/rtabmapviz: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10).
/rtabmap/rtabmapviz subscribed to (approx sync):
   /rtabmap/odom,
   /camera/rgb/image_rect_color,
   /camera/depth_registered/image_raw,
   /camera/rgb/camera_info,
   /rtabmap/odom_info

But when I echoed each topic some data is being published and I am able to get 2D map with this data. But I could not integrate 3D map to this odom and scan data. (odom = IMU and ENCODER data) I am actually trying to integrate gmapping and RTabmap and found a launch file that suits my requirements. I don't know whether it works. Here is the launch file I am using

<!-- Launch RTAB-map with Kinect2 and RPLidar A2 -->
<launch>
  <include file="$(find self_e)/launch/bringup.launch"/>
  <include file="$(find self_e)/launch/xbox.launch"/>
   <!-- Image resolution of the Kinect to process in rtabmap: sd, qhd, hd -->
   <arg name="resolution" default="qhd" />

   <!-- Fixed frame id -->
   <arg name="frame_id" default="base_link"/>  

   <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
    <remap from="scan" to="scan_filtered"/>
        <param name="base_frame" value="/base_footprint" />
        <param name="odom_frame" value="/odom" />
        <param name="map_update_interval" value="5.0"/>
        <param name="maxUrange" value="5.5"/>
        <param name="minRange" value="-0.5"/>
        <param name="sigma" value="0.05"/>
        <param name="kernelSize" value="1"/>
        <param name="lstep" value="0.05"/>
        <param name="astep" value="0.05"/>
        <param name="iterations" value="5"/>
        <param name="lsigma" value="0.075"/>
        <param name="ogain" value="3.0"/>
        <param name="lskip" value="0"/>
        <param name="minimumScore" value="50"/>
        <param name="srr" value="0.1"/>
        <param name="srt" value="0.2"/>
        <param name="str" value="0.1"/>
        <param name="stt" value="0.2"/>
        <param name="linearUpdate" value="0.2"/>
        <param name="angularUpdate" value="0.25"/>
        <param name="temporalUpdate" value="5.0"/>
        <param name="resampleThreshold" value="0.5"/>
        <param name="particles" value="50"/>
        <param name="xmin" value="-30.0"/>
        <param name="ymin" value="-30.0"/>
        <param name="xmax" value="30.0"/>
        <param name="ymax" value="30.0"/>
        <param name="delta" value="0.025"/>
        <param name="llsamplerange" value="0.01"/>
        <param name="llsamplestep" value="0.01"/>
        <param name="lasamplerange" value="0.005"/>
        <param name="lasamplestep" value="0.005"/>
        <param name="transform_publish_period" value="0.1"/>
   </node>

   <group ns="rtabmap">    
        <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
            <param name="subscribe_depth"      type="bool"    value="true"/>
            <param name="frame_id"             type="string"  value="$(arg frame_id)"/>
            <param name="subscribe_scan"       type="bool"    value="true"/>            
            <param name="Grid/DepthDecimation"                    value="2"/> 
            <param name ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-08-30 10:15:04 -0600

matlabbe gravatar image

Having slam_gmapping and rtabmap running at the same time is not very useful and it can potentially break the TF tree as they would publish the same TF (/map->/odom). They are both SLAM approaches, they are not meant to be working together. Choose one or the other.

For rtabmap, in the output of rostopic hz, we cannot see if /camera/depth/image_rect is published. If not, it could be the problem. If it is published, you may increase the queue_size parameter to be able to synchronize the topics with different frame rate.

Another note, if your odometry from IMU+Encoders is not very accurate, it is posible to refine odometry with the scan in rtabmap by setting RGBD/NeighborLinkRefining to true (similarly to Kinect+Odometry+2D laser example).

The voxel_cloud is only used for visualization. It constructs a point cloud from RGB-D images to be visualized in RVIZ.

edit flag offensive delete link more

Comments

I have edited /camera/depth/image_rect to /camera/depth_registered/image_raw and it is being published. I have also changed

<remap from="scan"                 to="/scan_filtered"/>
<remap from="odom"                 to="/odom"/>

and i am getting this error stated in below comment.

NAGALLA DEEPAK gravatar image NAGALLA DEEPAK  ( 2018-08-30 10:47:53 -0600 )edit

[FATAL] (2018-08-30 21:09:57.861) util3d_mapping.cpp:810::rayTrace() Condition (end.x >= 0 && end.x < grid.cols) not met! [end.x=236 grid.cols=191]

and the one stated in below comment

NAGALLA DEEPAK gravatar image NAGALLA DEEPAK  ( 2018-08-30 10:48:50 -0600 )edit

[rtabmap/rtabmap-27] process has died [pid 4668, exit code -6, cmd /home/user/mapping/devel/lib/rtabmap_ros/rtabmap --delete_db_on_start rgb/image:=/camera/rgb/image_rect_color depth/image:=/camera/depth_registered/image_raw rgb/camera_info:=/camera/rgb/camera_info depth_camera_info_topic:=/camera/d

NAGALLA DEEPAK gravatar image NAGALLA DEEPAK  ( 2018-08-30 10:49:03 -0600 )edit

Gmapping is running well which means sacn and odom are being published but rtabmap is dying. This is happening only when I use the above topics else the process is not dying but the same warning as stated in question is coming. waiting for data..........

NAGALLA DEEPAK gravatar image NAGALLA DEEPAK  ( 2018-08-30 10:50:27 -0600 )edit
1

This is an issue with the released binaries version when Grid/CellSize is set to 1 cm, that issue is fixed in latest source code (see this issue). Set it back to 5 cm as a workaround if you don't want to rebuild rtabmap from source.

matlabbe gravatar image matlabbe  ( 2018-08-30 14:13:49 -0600 )edit

Thankyou, I am able to run both gmapping and RTabMap simultaneously now. Have to test how perfect and clear the 3D map is......but could I ask you for more information about what Grid/CellSize is?

NAGALLA DEEPAK gravatar image NAGALLA DEEPAK  ( 2018-08-31 01:41:28 -0600 )edit
1

It is the size of the occupancy grid's cells. I think gmapping also uses 5 cm by default. In your gmapping config, you set it to 2.5 cm. (<param name="delta" value="0.025"/>).

matlabbe gravatar image matlabbe  ( 2018-08-31 06:39:52 -0600 )edit

Oh! thank you so much

NAGALLA DEEPAK gravatar image NAGALLA DEEPAK  ( 2018-10-04 01:38:12 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2018-08-29 09:19:39 -0600

Seen: 1,022 times

Last updated: Aug 30 '18