introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
952 stars 556 forks source link

rviz doesn't map much and is not the same as rtabmapviz #874

Open khuechuong opened 1 year ago

khuechuong commented 1 year ago

Basically, I am using a zed mini and using their ROS package. I use ubuntu 20.04, ros noetic, ros1, with a gtx 1080 gpu. I follow the installation instruction: https://www.stereolabs.com/docs/ros/ And I used rtabmap ros. In the beginning, both rtabmapviz and rviz wasn't that good as seen here.

RVIZ with _/zed/zed_node/point_cloud/cloudregistered topic: Screenshot from 2023-01-20 00-26-16

RVIZ without _/zed/zed_node/point_cloud/cloudregistered topic: Screenshot from 2023-01-20 00-26-38

So I changed the param _subscribe_scancloud to true and add to rtabmap_ros and rtabmapviz. That really helped rtabmapviz, but rviz still just doesn't have the good quality of mapping like I see in other youtube. The command I ran was _roslaunch zed_rtabmap_example zedrtabmap.launch

zed_rtabmap.launch

<?xml version="1.0"?>

sl_rtabmap.launch.xml

rtabmap.yaml subscribe_depth: true subscribe_rgbd: false subscribe_stereo: false subscribe_stereo: false subscribe_scan: false subscribe_scan_cloud: true subscribe_user_data: false subscribe_odom_info: false

database_path: "~/.ros/rtabmap.db" config_path: "~/.ros/rtabmap.cfg"

frame_id: "base_link" map_frame_id: "map" odom_frame_id: "odom" # odometry from odom msg to have covariance - Remapped by launch file odom_tf_angular_variance: 0.001 # If TF is used to get odometry, this is the default angular variance odom_tf_linear_variance: 0.001 # If TF is used to get odometry, this is the default linear variance tf_delay: 0.02 publish_tf: false # Set to false if fusing different poses (map->odom) with UKF

odom_sensor_sync: true wait_for_transform_duration: 0.2 approx_sync: true

queue_size: 100

scan_normal_k: 0

Grid: 3D: true FlatObstacleDetected: true MapFrameProjection: false GroundIsObstacle: false PreVoxelFiltering: true RayTracing: true FromDepth: true NormalsSegmentation: false CellSize: 0.05 ClusterRadius: 0.1 MinClusterSize: 3 DepthDecimation: 1 DepthRoiRatios: [0.0, 0.0, 0.0, 0.0] FootprintHeight: 2.0 FootprintLength: 0.18 FootprintWidth: 0.18 MaxGroundAngle: 30.0 MinGroundHeight: -0.5 MaxGroundHeight: -0.4 MaxObstacleHeight: 0.1 NoiseFilteringMinNeighbors: 5 NoiseFilteringRadius: 0.1 NormalK: 20 RangeMin: 0.7 RangeMax: 3.0

GridGlobal: Eroded: false # Erode obstacle cells FootprintRadius: 0.18 # Footprint radius (m) used to clear all obstacles under the graph FullUpdate: true # When the graph is changed, the whole map will be reconstructed instead of moving individually each cells of the map. Also, data added to cache won't be released after updating the map. This process is longer but more robust to drift that would erase some parts of the map when it should not MaxNodes: 0 # Maximum nodes assembled in the map starting from the last node (0=unlimited) MinSize: 1.0 # Minimum map size (m) OccupancyThr: 0.55 # Occupancy threshold (value between 0 and 1) ProbClampingMax: 0.971 # Probability clamping maximum (value between 0 and 1) ProbClampingMin: 0.1192 # Probability clamping minimum (value between 0 and 1) ProbHit: 0.7 # Probability of a hit (value between 0.5 and 1) ProbMiss: 0.4 # Probability of a miss (value between 0 and 0.5) UpdateError: 0.01 # Graph changed detection error (m). Update map only if poses in new optimized graph have moved more than this value

Here's a picture of what it looks like:

RVIZ with _/zed/zed_node/point_cloud/cloudregistered topic: Screenshot from 2023-01-20 00-33-14

RVIZ with _/zed/zed_node/point_cloud/cloudregistered topic: Screenshot from 2023-01-20 00-34-05

As you can see, in rtabmapviz, the quality improved drastically, but rviz mapping mapping points barely had anything. I don't really understand why. Any thought and help is appreciated. Let me know if you have any questions. Thank you!

matlabbe commented 1 year ago

In rviz, use rtabmap_ros/MapCloud display (on /rtabmap/mapData topic) instead of a PointCloud2 display. The rtabmap/cloud_map topic contains very downsampled point cloud for occupancy grid. In your second screen shot, you can see the point cloud in rtabmapviz has more points than in rviz. You should get something similar in rviz with MapCloud rviz display. You can then adjust the decimation value (default 4) to show more or less points. Don't use subscribe_scan_cloud with point cloud generated from cameras (unless they are TOF cameras), it is mainly used for 3D lidars.

khuechuong commented 1 year ago

Is zed mini a TOF cameras?

matlabbe commented 1 year ago

No, it is stereo

khuechuong commented 1 year ago

Okay so I did what you said minus the subscribe scan cloud since it looks pretty bad without it. I got this:

image

I see the decimation to max and it still doesn't capture enough to make solids like rtamapviz

matlabbe commented 1 year ago

Set cloud decimation to 1, and voxel to 0 to get all points.

khuechuong commented 1 year ago

when I set the cloud vortex size to 0, the whole map stop working.

matlabbe commented 1 year ago

The problem is that converting depth to point cloud without any decimation and voxel downsampling requires quite a lot of rendering power. You may increase decimation to 2 or 4 if you set voxel size to 0. In rtabmapviz, by default the depth image is created with decimation 4 without voxel filtering.

matlabbe commented 1 year ago

Just tested with a ZED2 and default zed_rtabmap.launch, and it works as expected. Here comparison between rtabmapviz and rviz (using MapCloud plugin with default values): Screenshot from 2023-01-28 16-48-35

khuechuong commented 1 year ago

The accuracy is less than I thought. I thought it would be more solid. Also I have a zed mini, I don't know if there are performance difference between the 2

Myzhar commented 1 year ago

@khuechuong what depth mode and resolution are you using? Have you tried to set depth_quality to 4 (NEURAL)?

khuechuong commented 1 year ago

@Myzhar I used 1 but I'll try 4 and see