Robosense RS-Bpearl mapping

classic Classic list List threaded Threaded
3 messages Options
Reply | Threaded
Open this post in threaded view
|

Robosense RS-Bpearl mapping

matlabbe
Administrator
Hi,

Posting here an example launch file to use RS-BPearl data for mapping:

roslaunch rtabmap_ros rtabmap.launch    \
   use_sim_time:=false \
   depth:=false \
   subscribe_scan_cloud:=true \
   frame_id:=rslidar \
   scan_cloud_topic:=/rslidar_points \
   scan_cloud_max_points:=64000  \
   icp_odometry:=true \
   approx_sync:=false \
   scan_cloud_assembling:=true \
   scan_cloud_assembling_time:=0 \
   scan_cloud_assembling_max_clouds:=5 \
   args:="-d  \
      --RGBD/CreateOccupancyGrid false \
      --Rtabmap/DetectionRate 0 \
      --Odom/ScanKeyFrameThr 0.8 \
      --OdomF2M/ScanMaxSize 20000  \
      --OdomF2M/ScanSubtractRadius 0.5   \
      --Icp/PM true \
      --Icp/VoxelSize 0.5   \
      --Icp/MaxTranslation 2   \
      --Icp/MaxCorrespondenceDistance 1.5 \
      --Icp/PMOutlierRatio 0.7 \
      --Icp/Iterations 10 \
      --Icp/PointToPlane false \
      --Icp/PMMatcherKnn 3 \
      --Icp/PMMatcherEpsilon 1 \
      --Icp/Epsilon 0.0001 \
      --Icp/PointToPlaneK 10 \
      --Icp/PointToPlaneRadius 0 \
      --Icp/CorrespondenceRatio 0.01"

roslaunch rslidar_sdk start.launch

Here some results from a PCAP with the sensor on a car looking towards the side of the road:




The red line is a measurement of around 75 meters from the lidar.

Reply | Threaded
Open this post in threaded view
|

Re: Robosense RS-Bpearl mapping

Josja
Thanks for posting this! What version of RTAB-Map did you use? I'm testing with building from src with libpointmatcher, are you using anything different?
Reply | Threaded
Open this post in threaded view
|

Re: Robosense RS-Bpearl mapping

matlabbe
Administrator
This was done with latest version built from source with libpointmatcher support.