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

Unable to build RTAB map using 2d rotating LiDAR [closed]

asked 2019-06-26 14:29:37 -0500

tsdk00 gravatar image

updated 2019-06-29 01:25:03 -0500

Hi,

I'm using a rotating 2d lidar and then using laser assembler package to get 3d point cloud. Video

I can see the point cloud but when I used in RTAB no map frame is generated neither it is able to map the data. Here is my launch file

    <?xml version="1.0" encoding="UTF-8"?>
    <launch>
      <!-- Mapping -->
      <group ns="rtabmap">

    <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap">
       <param name="subscribe_depth"      type="bool"   value="false"/>
       <param name="subscribe_rgb"        type="bool"   value="false"/>
       <param name="subscribe_scan_cloud" type="bool"   value="true"/>

       <remap from="scan_cloud" to="/laser_pointcloud"/> <!-- sensor_msgs/PointCloud2 -->
       <remap from="odom"       to="/odom"/> <!-- odometry from wheel encoders + IMU fusion -->

      <!-- output -->
   <remap from="grid_map" to="/map"/>

    </node>
 <!-- <node name="rviz" pkg="rviz" type="rviz"  args="-d $(find rtabmap_ros)/launch/config/turtlebot_navigation.rviz"/> -->    
  </group>
</launch>

I'm not sure if it is because of the rotating laser transform to the base link is being received properly or not. You can see the tf tree as no map frame is published Frames

Can anyone help me? Warning

[Updated] image description image description

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by tsdk00
close date 2019-07-02 13:32:06.876880

Comments

If /map -> /odom frame is not published, it means rtabmap is not started because it didn't receive topics yet. Do you have warnings on terminal if you set <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen">?

matlabbe gravatar image matlabbe  ( 2019-06-27 10:58:09 -0500 )edit

@matlabbe Here is the Warning message as updated above

You can also look at my bag file. The issue what I think is since it is doing a vertical scan so it is not getting enough point cloud data to produce the 3d map. So eventually some accumulated laser scan has to be provided. I tried the same bag file with cartographer and there is a parameter in Cartographer to provide accumulated laser scan data. So when I set it to 40, I can get a 3d map. BAG

tsdk00 gravatar image tsdk00  ( 2019-06-27 12:33:43 -0500 )edit

Thanks for your reply. Yeah, it works.No more warnings. Just wanted to know would it be ideal to make the /laser_pointcloud and /odom published at the same rate? I updated the rate figure above and changed the queue_size to 50.

rosrun rtabmap_ros rtabmap -d _subscribe_depth:=false _subscribe_rgb:=false _subscribe_scan_cloud:=true scan_cloud:=/laser_pointcloud odom:=/odom  _approx_sync:=true _queue_size:=50

And just last question, which point_cloud data in rviz you subscribed to get that map. I mean there are many point_cloud data and I'm getting this as updated above in the main question.

tsdk00 gravatar image tsdk00  ( 2019-06-29 01:21:45 -0500 )edit

You could have kept it to 500Hz, but more time/memory would be used to manage the synchronization queue. My concern is if the queue could eventually have 500 scans at the same time, not sure if message_filters discard automatically older scan msgs if all 500 of odom are more recent. Maybe it is negligible too. Another way is to subscribe to TF for odometry instead, with _odom_frame_id:="odom" _odom_tf_angular_variance:=0.0005 _odom_tf_angular_variance:=0.0001

For your last question, you seem using cloud_map topic, which is voxelized at 5 cm by default. I was showing the one built from rtabmap_ros/MapCloud rviz plugin (available only with latest version and check "Cloud from scan" checkbox).

matlabbe gravatar image matlabbe  ( 2019-07-02 13:26:15 -0500 )edit

Yeah, will try. But the plots look eventually fine. Thanx a lot for your help

tsdk00 gravatar image tsdk00  ( 2019-07-02 13:31:26 -0500 )edit

Hi, @tsdk00 could you send me your bag file? (it's not downloadable now)

Hamid Didari gravatar image Hamid Didari  ( 2021-06-10 08:21:47 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2019-06-28 11:14:39 -0500

matlabbe gravatar image

Hi, thx for the bag. The /odom tropic is published at >500Hz and /laser_pointcloud is 1 Hz. The queue_size should be then around 500! approx_sync should be also true (false in your warning saying exact sync is used). The TF /odom -> /base_link seems to give a lot of Detected jump back in time of 0.000423494s. Clearing TF buffer. warnings. You could decrease odometry frame rate to 50 Hz or 20 Hz. With the following, I am still able to have a map:

$ roscore
$ rosparam set use_sim_time true
$ rosbag play --clock rotating_lidar_straight_pipe.bag
$ rosrun rtabmap_ros rtabmap -d _subscribe_depth:=false _subscribe_rgb:=false _subscribe_scan_cloud:=true scan_cloud:=/laser_pointcloud odom:=/odom  _approx_sync:=true _queue_size:=500

image description

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-06-26 14:29:37 -0500

Seen: 537 times

Last updated: Jun 29 '19