ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Thx for the db, there are some observations that we can make (referring to figure below):
The resulting depth image from the sensor is quite noisy (see top view of the cloud on right image). I suggest to use Grid/3D=false
and Grid/RayTracing=true
to get more empty cells (see grid on left image):
$ roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="--delete_db_on_start --Grid/3D false --Grid/RayTracing true" depth_topic:=/camera/aligned_depth_to_color/image_raw rgb_topic:=/camera/color/image_raw camera_info_topic:=/camera/color/camera_info approx_sync:=false
There is quite motion blur when the robot moves (see top middle image, open image in another tab to zoom in), which would affect visual odometry accuracy.
Solutions:
Tilt the camera toward the ceiling (and/or increase height) so that there is less ground in the FOV of the camera. Make sure to update TF as well between base_link and camera_link.
Consider using wheel odometry if possible
2 | No.2 Revision |
Thx for the db, there are some observations that we can make (referring to figure below):
The resulting depth image from the sensor is quite noisy (see top view of the cloud on right image). I suggest to use Grid/3D=false
and Grid/RayTracing=true
to get more empty cells (see grid on left image):
$ roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="--delete_db_on_start --Grid/3D false --Grid/RayTracing true" depth_topic:=/camera/aligned_depth_to_color/image_raw rgb_topic:=/camera/color/image_raw camera_info_topic:=/camera/color/camera_info approx_sync:=false
There is quite motion blur when the robot moves (see top middle image, open image in another tab to zoom in), which would affect visual odometry accuracy.
Solutions:
Tilt the camera toward the ceiling (and/or increase height) so that there is less ground in the FOV of the camera. Make sure to update TF as well between base_link and camera_link.
Move slower to limit motion blur
Consider using wheel odometry if possible
3 | No.3 Revision |
Thx for the db, there are some observations that we can make (referring to figure below):
The resulting depth image from the sensor is quite noisy (see top view of the cloud on right image). I suggest to use Grid/3D=false
and Grid/RayTracing=true
to get more empty cells (see grid on left image):
$ roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="--delete_db_on_start --Grid/3D false --Grid/RayTracing true" depth_topic:=/camera/aligned_depth_to_color/image_raw rgb_topic:=/camera/color/image_raw camera_info_topic:=/camera/color/camera_info approx_sync:=false
There is quite motion blur when the robot moves (see top middle image, open image in another tab to zoom in), which would affect visual odometry accuracy.
Solutions:Possible solutions:
Tilt the camera toward the ceiling (and/or increase height) so that there is less ground in the FOV of the camera. Make sure to update TF as well between base_link and camera_link.
Move slower to limit motion blur
Consider using wheel odometry if possible