import launch from launch_ros.actions import Node from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration def generate_launch_description(): # 定义启动参数 use_sim_time = LaunchConfiguration('use_sim_time', default='false') # RPLidar A1 节点 rplidar_node = Node( package='rplidar_ros', executable='rplidar_node', name='rplidar_node', parameters=[{ 'serial_port': '/dev/rplidar', 'serial_baudrate': 115200, 'frame_id': 'laser', 'inverted': False, 'angle_compensate': True, 'scan_mode': 'Standard' }], output='screen' ) # slam_toolbox 节点 slam_toolbox_node = Node( package='slam_toolbox', executable='async_slam_toolbox_node', name='slam_toolbox', output='screen', parameters=[{ 'use_sim_time': use_sim_time, 'map_frame': 'map', 'odom_frame': 'odom', 'base_frame': 'base_link', 'scan_topic': '/scan', 'mode': 'mapping', # 建图模式 'resolution': 0.05, # 地图分辨率 'max_laser_range': 12.0, # 最大激光范围 }] ) # 静态TF发布 - 定义雷达位置 static_tf_laser = Node( package='tf2_ros', executable='static_transform_publisher', name='static_transform_publisher_laser', arguments=['0', '0', '0.1', '0', '0', '0', 'base_link', 'laser'] ) # 静态TF发布 - 定义base_link到odom的初始位置 static_tf_odom = Node( package='tf2_ros', executable='static_transform_publisher', name='static_transform_publisher_odom', arguments=['0', '0', '0', '0', '0', '0', 'odom', 'base_link'] ) return launch.LaunchDescription([ DeclareLaunchArgument('use_sim_time', default_value='false'), rplidar_node, static_tf_laser, static_tf_odom, slam_toolbox_node, ])