""" rplidar.launch.py — RPLIDAR A1M8 driver (standalone) Launches rplidar_ros with udev symlink (/dev/rplidar) set in 99-saltybot.rules. Falls back to /dev/ttyUSB0 if the symlink is not present. RPLIDAR A1M8 specs: - 360° omnidirectional scan - 8000 samples/s, ~5.5 Hz scan rate at 1440 points/scan - 12m range (reliable to ~8m indoors) - 115200 baud via CP2102 USB-UART adapter Published topics: /scan sensor_msgs/LaserScan ~5.5 Hz TF frame: laser → matches static_transform_publisher in sensors.launch.py frame_id = 'laser' Verify: ros2 topic hz /scan ros2 run tf2_ros tf2_echo base_link laser """ import os from launch import LaunchDescription from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration from ament_index_python.packages import get_package_share_directory def generate_launch_description(): serial_port_arg = DeclareLaunchArgument( 'serial_port', default_value='/dev/rplidar', description='RPLIDAR serial port (udev symlink preferred over /dev/ttyUSB0)', ) rplidar_share = get_package_share_directory('rplidar_ros') rplidar_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( os.path.join(rplidar_share, 'launch', 'rplidar_a1_launch.py') ), launch_arguments={ 'serial_port': LaunchConfiguration('serial_port'), 'serial_baudrate': '115200', # 'laser' matches the TF frame in sensors.launch.py and slam config 'frame_id': 'laser', # Compensate for motor rotation angle offset 'angle_compensate': 'true', # A1M8 only supports Standard scan mode 'scan_mode': 'Standard', }.items(), ) return LaunchDescription([ serial_port_arg, rplidar_launch, ])