From d00598d72c8d9beba0911f03a0e95eccdb7b0d23 Mon Sep 17 00:00:00 2001 From: SimonR99 Date: Sun, 9 Jun 2024 22:57:29 -0400 Subject: [PATCH] slam 3d basic real hardware --- src/rove_bringup/launch/autonomy.launch.py | 6 +++--- src/rove_slam/launch/slam.launch.py | 2 +- src/rove_slam/launch/slam3d.launch.py | 12 ++---------- 3 files changed, 6 insertions(+), 14 deletions(-) diff --git a/src/rove_bringup/launch/autonomy.launch.py b/src/rove_bringup/launch/autonomy.launch.py index bf0132b..64c1db7 100644 --- a/src/rove_bringup/launch/autonomy.launch.py +++ b/src/rove_bringup/launch/autonomy.launch.py @@ -6,7 +6,7 @@ from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration -from launch.conditions import IfCondition +from launch.conditions import IfCondition, UnlessCondition def generate_launch_description(): @@ -29,7 +29,7 @@ def generate_launch_description(): pkg_rove_slam, "config", "slam_config.yaml" ) }.items(), - condition=IfCondition(use_slam3d) + condition=UnlessCondition(use_slam3d) ) slam3d = IncludeLaunchDescription( @@ -53,7 +53,7 @@ def generate_launch_description(): ) return LaunchDescription([ - #slam, + slam, slam3d, nav, ]) diff --git a/src/rove_slam/launch/slam.launch.py b/src/rove_slam/launch/slam.launch.py index 569ad47..0f0b729 100644 --- a/src/rove_slam/launch/slam.launch.py +++ b/src/rove_slam/launch/slam.launch.py @@ -9,7 +9,7 @@ def generate_launch_description(): pkg_rove_slam = get_package_share_directory('rove_slam') config_file = os.path.join(pkg_rove_slam, 'config', - 'mapper_params_online_async.yaml') + 'slam_config.yaml') return LaunchDescription([ Node( diff --git a/src/rove_slam/launch/slam3d.launch.py b/src/rove_slam/launch/slam3d.launch.py index 8b22f22..00710e6 100644 --- a/src/rove_slam/launch/slam3d.launch.py +++ b/src/rove_slam/launch/slam3d.launch.py @@ -8,20 +8,15 @@ def generate_launch_description(): camera_model = 'zed2i' 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', + 'use_sim_time', default_value='false', description='Use simulation (Gazebo) clock if true'), DeclareLaunchArgument( @@ -32,7 +27,6 @@ def generate_launch_description(): 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, @@ -73,7 +67,6 @@ def generate_launch_description(): 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, @@ -118,7 +111,6 @@ def generate_launch_description(): 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,