Skip to content

Commit

Permalink
vlp example: moved rtabmap's parameters from arguments to parameters …
Browse files Browse the repository at this point in the history
…to avoid string parameter conversion errors like #1134
  • Loading branch information
matlabbe committed Mar 24, 2024
1 parent 9fc7212 commit bfef9ee
Showing 1 changed file with 38 additions and 38 deletions.
76 changes: 38 additions & 38 deletions rtabmap_examples/launch/vlp16.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,26 +37,25 @@ def generate_launch_description():
'expected_update_rate':15.0,
'deskewing':deskewing,
'use_sim_time':use_sim_time,
# RTAB-Map's internal parameters are strings:
'Icp/PointToPlane': 'true',
'Icp/Iterations': '10',
'Icp/VoxelSize': '0.1',
'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'
}],
remappings=[
('scan_cloud', '/velodyne_points')
],
arguments=[
'Icp/PointToPlane', 'true',
'Icp/Iterations', '10',
'Icp/VoxelSize', '0.1',
'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(
Expand All @@ -80,32 +79,33 @@ def generate_launch_description():
'approx_sync':False,
'wait_for_transform':0.2,
'use_sim_time':use_sim_time,
# RTAB-Map's internal parameters are strings:
'RGBD/ProximityMaxGraphDepth': '0',
'RGBD/ProximityPathMaxNeighbors': '1',
'RGBD/AngularUpdate': '0.05',
'RGBD/LinearUpdate': '0.05',
'RGBD/CreateOccupancyGrid': 'false',
'Mem/NotLinkedNodesKept': 'false',
'Mem/STMSize': '30',
'Mem/LaserScanNormalK': '20',
'Reg/Strategy': '1',
'Icp/VoxelSize': '0.1',
'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'
}],
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', 'false',
'Mem/NotLinkedNodesKept', 'false',
'Mem/STMSize', '30',
'Mem/LaserScanNormalK', '20',
'Reg/Strategy', '1',
'Icp/VoxelSize', '0.1',
'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',
'-d' # This will delete the previous database (~/.ros/rtabmap.db)
]),

Node(
Expand Down

0 comments on commit bfef9ee

Please sign in to comment.