Skip to content

Commit

Permalink
add slam 3d
Browse files Browse the repository at this point in the history
  • Loading branch information
SimonR99 committed Apr 6, 2024
1 parent 7f141eb commit 793527a
Show file tree
Hide file tree
Showing 4 changed files with 149 additions and 3 deletions.
11 changes: 11 additions & 0 deletions src/rove_description/launch/sim.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,16 @@ def generate_launch_description():
}.items(),
)

slam3d = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_rove_slam, "launch", "slam3d.launch.py"),
),
launch_arguments={
"use_sim_time": "true",
"deskewing": "true",
}.items(),
)

nav = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_rove_nav, "navigation.launch.py"),
Expand All @@ -117,6 +127,7 @@ def generate_launch_description():
robot_localization_node,
rviz,
slam,
#slam3d,
create,
nav,
])
131 changes: 131 additions & 0 deletions src/rove_slam/launch/slam3d.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,131 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node

def generate_launch_description():

lidar_frame_id = LaunchConfiguration('lidar_frame_id')

use_sim_time = LaunchConfiguration('use_sim_time')
deskewing = False

return LaunchDescription([


DeclareLaunchArgument(
'lidar_frame_id', default_value='velodyne_laser',
description='Lidar frame id'),

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

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

# Nodes to launch
Node(
package='rtabmap_odom', executable='icp_odometry', output='screen',
parameters=[{
'frame_id': lidar_frame_id, # 'livox_frame'
'odom_frame_id': 'odom',
'wait_for_transform': 0.2,
'expected_update_rate': 50.0,
'deskewing': deskewing,
'use_sim_time': use_sim_time,
}],
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(
package='rtabmap_util', executable='point_cloud_assembler', output='screen',
parameters=[{
'max_clouds': 10,
'fixed_frame_id': '',
'use_sim_time': use_sim_time,
}],
remappings=[
('cloud', '/velodyne_points')
]),

Node(
package='rtabmap_slam', executable='rtabmap', output='screen',
parameters=[{
'frame_id': lidar_frame_id, # 'livox_frame'
'subscribe_depth': False,
'subscribe_rgb': False,
'subscribe_scan_cloud': True,
'approx_sync': False,
'wait_for_transform': 0.2,
'use_sim_time': use_sim_time,
'wait_imu_to_int': True,
'imu_topic': 'imu',
}],
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.5',
'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',
'Grid/MaxGroundHeight', '0.05',
'Grid/MaxObstacleHeight', '1.5',
'Reg/Force3DoF', 'true',
'Optimizer/Slam2D', 'true',

]),

Node(
package='rtabmap_viz', executable='rtabmap_viz', output='screen',
parameters=[{
'frame_id': lidar_frame_id,
'odom_frame_id': 'odom',
'subscribe_odom_info': True,
'subscribe_scan_cloud': True,
'approx_sync': False,
'use_sim_time': use_sim_time,
}],
remappings=[
('scan_cloud', 'odom_filtered_input_scan')
]),
])

8 changes: 6 additions & 2 deletions src/rove_slam/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,12 @@
<license>TODO: License declaration</license>


<exec_depend>slam_toolbox</exec_depend>
<exec_depend>robot_localization</exec_depend>
<build_depend>slam_toolbox</build_depend>
<build_depend>robot_localization</build_depend>
<build_depend>rtabmap</build_depend>
<build_depend>rtabmap_odom</build_depend>
<build_depend>rtabmap_slam</build_depend>
<build_depend>rtabmap_viz</build_depend>


<test_depend>ament_copyright</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion src/rove_slam/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name), glob('launch/*.launch.py')),
('share/' + package_name + '/launch', glob('launch/*.launch.py')),
('share/' + package_name + '/config', glob('config/*')),
],
install_requires=['setuptools'],
Expand Down

0 comments on commit 793527a

Please sign in to comment.