introlab / rtabmap_ros

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

Weird map is created with ICP odometry and lidar #1012

Open sagarvl96 opened 1 year ago

sagarvl96 commented 1 year ago

I am trying to map with a Bpearl lidar. The launch file I am using is as follows:

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node

def generate_launch_description():

    use_sim_time = LaunchConfiguration('use_sim_time')
    deskewing = LaunchConfiguration('deskewing')

    return LaunchDescription([

        # Launch arguments
        DeclareLaunchArgument(
            'use_sim_time', default_value='false',
            description='Use simulation (Gazebo) clock if true'),

        DeclareLaunchArgument(
            'deskewing', default_value='false',
            description='Enable lidar deskewing'),

        # Nodes to launch
        Node(
            package='rtabmap_odom', executable='icp_odometry', output='screen',
            parameters=[{
              'frame_id':'robot_base_footprint',
              'odom_frame_id':'odom',
              'wait_for_transform':0.2,
              'expected_update_rate':15.0,
              'deskewing':deskewing,
              'use_sim_time':use_sim_time,
            }],
            remappings=[
              ('scan_cloud', '/robot/bpearl_laser/scan')
            ],
            arguments=[
              'Icp/PointToPlane', 'true',
              'Icp/Iterations', '10',
              'Icp/VoxelSize', '0',
              'Icp/Epsilon', '0.001',
              'Icp/PointToPlaneK', '20',
              'Icp/PointToPlaneRadius', '0',
              'Icp/MaxTranslation', '2',
              'Icp/MaxCorrespondenceDistance', '1',
              'Icp/Strategy', '1',
              'Icp/OutlierRatio', '0.7',
              'Icp/CorrespondenceRatio', '0.01',
              'Odom/ScanKeyFrameThr', '0.4',
              'OdomF2M/ScanSubtractRadius', '0.1',
              'OdomF2M/ScanMaxSize', '15000',
              'OdomF2M/BundleAdjustment', 'false',
            ]),

        Node(
            package='rtabmap_util', executable='point_cloud_assembler', output='screen',
            parameters=[{
              'max_clouds':10,
              'fixed_frame_id':'',
              'use_sim_time':use_sim_time,
            }],
            remappings=[
              ('cloud', 'odom_filtered_input_scan')
            ]),

        Node(
            package='rtabmap_slam', executable='rtabmap', output='screen',
            parameters=[{
              'frame_id':'robot_base_footprint',
              'subscribe_depth':False,
              'subscribe_rgb':False,
              'subscribe_scan_cloud':True,
              'approx_sync':False,
              'wait_for_transform':0.2,
              'use_sim_time':use_sim_time,
            }],
            remappings=[
              ('scan_cloud', 'assembled_cloud')
            ],
            arguments=[
              '-d', # This will delete the previous database (~/.ros/rtabmap.db)
              'RGBD/ProximityMaxGraphDepth', '0',
              'RGBD/ProximityPathMaxNeighbors', '1',
              'RGBD/AngularUpdate', '0.05',
              'RGBD/LinearUpdate', '0.05',
              'RGBD/CreateOccupancyGrid', 'true',
              'Mem/NotLinkedNodesKept', 'false',
              'Mem/STMSize', '30',
              'Mem/LaserScanNormalK', '20',
              'Reg/Strategy', '1',
              'Icp/VoxelSize', '0',
              'Icp/PointToPlaneK', '20',
              'Icp/PointToPlaneRadius', '0',
              'Icp/PointToPlane', 'true',
              'Icp/Iterations', '10',
              'Icp/Epsilon', '0.001',
              'Icp/MaxTranslation', '3',
              'Icp/MaxCorrespondenceDistance', '1',
              'Icp/Strategy', '1',
              'Icp/OutlierRatio', '0.7',
              'Icp/CorrespondenceRatio', '0.2',
            ]), 
    ])

The odom data is also generated as per the logs

icp_odometry-1] [INFO] [1690980855.593129608] [icp_odometry]: Odom: ratio=0.620365, std dev=0.000657m|0.000208rad, update time=0.350729s
[icp_odometry-1] [INFO] [1690980855.844427232] [icp_odometry]: Odom: ratio=0.597986, std dev=0.000692m|0.000219rad, update time=0.218086s
[icp_odometry-1] [INFO] [1690980856.129372510] [icp_odometry]: Odom: ratio=0.615104, std dev=0.000649m|0.000205rad, update time=0.228756s
[icp_odometry-1] [INFO] [1690980856.391427784] [icp_odometry]: Odom: ratio=0.620451, std dev=0.000102m|0.000173rad, update time=0.230934s
[icp_odometry-1] [INFO] [1690980856.622325676] [icp_odometry]: Odom: ratio=0.619427, std dev=0.000287m|0.000173rad, update time=0.188040s
[icp_odometry-1] [INFO] [1690980856.900350089] [icp_odometry]: Odom: ratio=0.615104, std dev=0.000625m|0.000198rad, update time=0.251112s
[icp_odometry-1] [INFO] [1690980857.239124068] [icp_odometry]: Odom: ratio=0.614097, std dev=0.000784m|0.000248rad, update time=0.314497s
[icp_odometry-1] [INFO] [1690980857.479946599] [icp_odometry]: Odom: ratio=0.606146, std dev=0.000239m|0.000173rad, update time=0.205755s
[icp_odometry-1] [INFO] [1690980857.714558420] [icp_odometry]: Odom: ratio=0.596267, std dev=0.000699m|0.000221rad, update time=0.207211s
[icp_odometry-1] [INFO] [1690980858.018100427] [icp_odometry]: Odom: ratio=0.582622, std dev=0.000799m|0.000253rad, update time=0.276070s
[icp_odometry-1] [INFO] [1690980858.368290221] [icp_odometry]: Odom: ratio=0.571146, std dev=0.000721m|0.000228rad, update time=0.314685s
[rtabmap-3] [INFO] [1690980858.605745555] [rtabmap]: rtabmap (1): Rate=1.00s, Limit=0.000s, Conversion=0.0084s, RTAB-Map=0.7023s, Maps update=0.0004s pub=0.0003s (local map=1, WM=1)
[icp_odometry-1] [INFO] [1690980858.740943205] [icp_odometry]: Odom: ratio=0.595174, std dev=0.000851m|0.000269rad, update time=0.344502s
[icp_odometry-1] [INFO] [1690980859.091804304] [icp_odometry]: Odom: ratio=0.605486, std dev=0.000705m|0.000223rad, update time=0.307818s

The tf tree also seems to be fine:

image

But the map that is generated has no differentiation between floor and walls.

image

Am I missing some parameter here?

matlabbe commented 1 year ago

Can you share the database?

sagarvl96 commented 1 year ago

Do you mean a rosbag file?

matlabbe commented 1 year ago

No the database that rtabmap created ~/.ros/rtabmap.db