Adds saltybot_bringup ROS2 package with four launch files: - realsense.launch.py — D435i at 640x480x15fps, IMU unified topic - rplidar.launch.py — RPLIDAR A1M8 via /dev/rplidar udev symlink - sensors.launch.py — both sensors + static TF (base_link→laser/camera) - slam.launch.py — sensors + slam_toolbox online_async (compose entry point) Sensor config YAMLs (mounted at /config/ in container): - realsense_d435i.yaml — Nano power-budget settings (15fps, no pointcloud) - rplidar_a1m8.yaml — Standard scan mode, 115200 baud, laser frame - slam_toolbox_params.yaml — Nano-tuned (2Hz processing, 5cm resolution) Fixes docker-compose volume mount: ./ros2_ws/src:/ros2_ws/src (was ./ros2_ws:/ros2_ws/src — would have double-nested the src directory) Topic reference and verification commands in SENSORS.md. Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
61 lines
1.9 KiB
Python
61 lines
1.9 KiB
Python
"""
|
|
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,
|
|
])
|