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>
31 lines
1.2 KiB
YAML
31 lines
1.2 KiB
YAML
# RPLIDAR A1M8 configuration
|
||
#
|
||
# Hardware specs:
|
||
# Model: RPLIDAR A1M8 (rev 6)
|
||
# Interface: USB-UART via CP2102 adapter (VID:10c4 PID:ea60)
|
||
# Baud rate: 115200
|
||
# Scan rate: ~5.5 Hz (1440 points/scan @ 8000 samples/s)
|
||
# Range: 0.15 m – 12 m (reliable to ~8 m indoors)
|
||
# Angular res: ~0.9° per sample
|
||
# Scan mode: Standard (A1M8 only supports this mode)
|
||
#
|
||
# udev symlink (from jetson/docs/pinout.md 99-saltybot.rules):
|
||
# /dev/rplidar → ttyUSB* where ATTRS{idVendor}=="10c4" ATTRS{idProduct}=="ea60"
|
||
#
|
||
# Published topics:
|
||
# /scan sensor_msgs/LaserScan ~5.5 Hz
|
||
# angle_min: -π rad (-180°)
|
||
# angle_max: +π rad (+180°)
|
||
# range_min: 0.15 m
|
||
# range_max: 12.0 m
|
||
# scan_time: ~0.182 s per revolution
|
||
|
||
rplidar_node:
|
||
ros__parameters:
|
||
serial_port: "/dev/rplidar" # udev symlink — stable across reboots
|
||
serial_baudrate: 115200
|
||
frame_id: "laser" # must match TF in sensors.launch.py
|
||
inverted: false # scan direction: false = counter-clockwise
|
||
angle_compensate: true # compensate for motor rotation offset
|
||
scan_mode: "Standard" # A1M8 only supports Standard mode
|