Implements full boot-time auto-start for the SaltyBot ROS2 stack on Jetson Orin. Everything comes up automatically after power-on with correct dependency ordering and restart-on-failure for each service. New systemd services: saltybot-ros2.service full_stack.launch.py (perception + SLAM + Nav2) saltybot-esp32-serial.service ESP32-S3 BALANCE UART bridge (bd-wim1, PR #727) saltybot-here4.service Here4 DroneCAN GPS bridge (bd-p47c, PR #728) saltybot-dashboard.service Web dashboard on port 8080 Updated: saltybot.target now Wants all four new services with boot-order comments can-bringup.service bitrate 500 kbps → 1 Mbps (DroneCAN for Here4) 70-canable.rules remove bitrate from udev RUN+=; let service own the bitrate, add TAG+=systemd for device unit install_systemd.sh installs all services + udev rules, colcon build, enables mosquitto, usermod dialout full_stack.launch.py resolve 8 merge conflict markers (ESP32-S3 rename) and fix missing indent on enable_mission_logging_arg — file was un-launchable with SyntaxError New: scripts/ros2-launch.sh sources ROS2 Humble + workspace overlay, then exec ros2 launch — used by all ROS2 service units via ExecStart= udev/80-esp32.rules /dev/esp32-balance (CH343) and /dev/esp32-io (ESP32-S3 native USB CDC) Resolves bd-1hyn Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
60 lines
1.9 KiB
Desktop File
60 lines
1.9 KiB
Desktop File
[Unit]
|
||
Description=SaltyBot ROS2 Full Stack (perception + navigation + SLAM)
|
||
Documentation=https://gitea.vayrette.com/seb/saltylab-firmware
|
||
#
|
||
# Launches: saltybot_bringup full_stack.launch.py (indoor mode by default)
|
||
# enable_bridge:=false — ESP32-S3 serial bridge is managed by saltybot-esp32-serial.service
|
||
#
|
||
# Stack launched (t=0s → t=17s):
|
||
# t= 0s robot_description (URDF + TF)
|
||
# t= 2s RPLIDAR A1M8 + RealSense D435i
|
||
# t= 3s LIDAR obstacle avoidance
|
||
# t= 4s 4× IMX219 CSI cameras (optional)
|
||
# t= 4s UWB driver
|
||
# t= 5s Audio pipeline (wake word + STT + TTS)
|
||
# t= 6s RTAB-Map SLAM (indoor) / GPS nav (outdoor)
|
||
# t= 6s YOLOv8n person + object detection (TensorRT)
|
||
# t= 7s Autonomous docking
|
||
# t= 9s Person follower
|
||
# t=14s Nav2 navigation stack
|
||
# t=17s rosbridge WebSocket (ws://0.0.0.0:9090)
|
||
#
|
||
# Hard deps: can-bringup (Here4 GPS topics), esp32-serial (VESC telemetry)
|
||
After=network-online.target can-bringup.service saltybot-esp32-serial.service saltybot-here4.service
|
||
Wants=can-bringup.service saltybot-esp32-serial.service saltybot-here4.service
|
||
|
||
[Service]
|
||
Type=simple
|
||
User=orin
|
||
Group=orin
|
||
|
||
Environment="ROS_DOMAIN_ID=42"
|
||
Environment="ROS_DISTRO=humble"
|
||
Environment="SALTYBOT_WS=/opt/saltybot/jetson/ros2_ws/install"
|
||
|
||
# enable_bridge:=false — ESP32 serial bridge runs as its own service (saltybot-esp32-serial)
|
||
# mode can be overridden via environment: Environment="SALTYBOT_MODE=outdoor"
|
||
ExecStart=/opt/saltybot/scripts/ros2-launch.sh \
|
||
saltybot_bringup full_stack.launch.py \
|
||
enable_bridge:=false \
|
||
mode:=${SALTYBOT_MODE:-indoor}
|
||
|
||
Restart=on-failure
|
||
RestartSec=10s
|
||
StartLimitInterval=120s
|
||
StartLimitBurst=3
|
||
|
||
TimeoutStartSec=120s
|
||
TimeoutStopSec=30s
|
||
|
||
# ROS2 launch spawns many child processes; kill them on stop
|
||
KillMode=control-group
|
||
|
||
# Logging
|
||
StandardOutput=journal
|
||
StandardError=journal
|
||
SyslogIdentifier=saltybot-ros2
|
||
|
||
[Install]
|
||
WantedBy=saltybot.target
|