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

Revision history [back]

click to hide/show revision 1
initial version

Thx for the db, there are some observations that we can make (referring to figure below):

  • The camera is very close to ground, so that the field of view is filled with more than 50% of repetitive symmetric pattern, very difficult to get good depth estimation as well for visual odometry. It is why the ground is poorly represented in the occupancy grid.
  • 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.

image description

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

Thx for the db, there are some observations that we can make (referring to figure below):

  • The camera is very close to ground, so that the field of view is filled with more than 50% of repetitive symmetric pattern, very difficult to get good depth estimation as well for visual odometry. It is why the ground is poorly represented in the occupancy grid.
  • 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.

image description

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

Thx for the db, there are some observations that we can make (referring to figure below):

  • The camera is very close to ground, so that the field of view is filled with more than 50% of repetitive symmetric pattern, very difficult to get good depth estimation as well for visual odometry. It is why the ground is poorly represented in the occupancy grid.
  • 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.

image description

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