Merge pull request 'feat: systemd auto-start for ROS2 + dashboard on Orin boot (bd-1hyn)' (#732) from sl-perception/bd-1hyn-orin-autostart into main
This commit is contained in:
commit
b353a2ba29
@ -39,11 +39,7 @@ Modes
|
|||||||
─ UWB driver (2-anchor DW3000, publishes /uwb/target)
|
─ UWB driver (2-anchor DW3000, publishes /uwb/target)
|
||||||
─ YOLOv8n person detection (TensorRT)
|
─ YOLOv8n person detection (TensorRT)
|
||||||
─ Person follower with UWB+camera fusion
|
─ Person follower with UWB+camera fusion
|
||||||
<<<<<<< HEAD
|
|
||||||
─ cmd_vel bridge → ESP32 BALANCE (deadman + ramp + AUTONOMOUS gate)
|
|
||||||
=======
|
|
||||||
─ cmd_vel bridge → ESP32-S3 (deadman + ramp + AUTONOMOUS gate)
|
─ cmd_vel bridge → ESP32-S3 (deadman + ramp + AUTONOMOUS gate)
|
||||||
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
|
||||||
─ rosbridge WebSocket (port 9090)
|
─ rosbridge WebSocket (port 9090)
|
||||||
|
|
||||||
outdoor
|
outdoor
|
||||||
@ -61,13 +57,8 @@ Modes
|
|||||||
Launch sequence (wall-clock delays — conservative for cold start)
|
Launch sequence (wall-clock delays — conservative for cold start)
|
||||||
─────────────────────────────────────────────────────────────────
|
─────────────────────────────────────────────────────────────────
|
||||||
t= 0s robot_description (URDF + TF tree)
|
t= 0s robot_description (URDF + TF tree)
|
||||||
<<<<<<< HEAD
|
|
||||||
t= 0s ESP32 bridge (serial port owner — must be first)
|
|
||||||
t= 2s cmd_vel bridge (consumes /cmd_vel, needs ESP32 bridge up)
|
|
||||||
=======
|
|
||||||
t= 0s ESP32-S3 bridge (serial port owner — must be first)
|
t= 0s ESP32-S3 bridge (serial port owner — must be first)
|
||||||
t= 2s cmd_vel bridge (consumes /cmd_vel, needs ESP32-S3 bridge up)
|
t= 2s cmd_vel bridge (consumes /cmd_vel, needs ESP32-S3 bridge up)
|
||||||
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
|
||||||
t= 2s sensors (RPLIDAR + RealSense)
|
t= 2s sensors (RPLIDAR + RealSense)
|
||||||
t= 4s UWB driver (independent serial device)
|
t= 4s UWB driver (independent serial device)
|
||||||
t= 4s CSI cameras (optional, independent)
|
t= 4s CSI cameras (optional, independent)
|
||||||
@ -80,17 +71,10 @@ Launch sequence (wall-clock delays — conservative for cold start)
|
|||||||
|
|
||||||
Safety wiring
|
Safety wiring
|
||||||
─────────────
|
─────────────
|
||||||
<<<<<<< HEAD
|
|
||||||
• ESP32 bridge must be up before cmd_vel bridge sends any command.
|
|
||||||
• cmd_vel bridge has 500ms deadman: stops robot if /cmd_vel goes silent.
|
|
||||||
• ESP32 BALANCE AUTONOMOUS mode gate (md=2) in cmd_vel bridge — robot stays still
|
|
||||||
until ESP32 BALANCE firmware is in AUTONOMOUS mode regardless of /cmd_vel.
|
|
||||||
=======
|
|
||||||
• ESP32-S3 bridge must be up before cmd_vel bridge sends any command.
|
• ESP32-S3 bridge must be up before cmd_vel bridge sends any command.
|
||||||
• cmd_vel bridge has 500ms deadman: stops robot if /cmd_vel goes silent.
|
• cmd_vel bridge has 500ms deadman: stops robot if /cmd_vel goes silent.
|
||||||
• ESP32-S3 AUTONOMOUS mode gate (md=2) in cmd_vel bridge — robot stays still
|
• ESP32-S3 AUTONOMOUS mode gate (md=2) in cmd_vel bridge — robot stays still
|
||||||
until ESP32-S3 firmware is in AUTONOMOUS mode regardless of /cmd_vel.
|
until ESP32-S3 firmware is in AUTONOMOUS mode regardless of /cmd_vel.
|
||||||
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
|
||||||
• follow_enabled:=false disables person follower without stopping the node.
|
• follow_enabled:=false disables person follower without stopping the node.
|
||||||
• To e-stop at runtime: ros2 topic pub /saltybot/estop std_msgs/Bool '{data: true}'
|
• To e-stop at runtime: ros2 topic pub /saltybot/estop std_msgs/Bool '{data: true}'
|
||||||
|
|
||||||
@ -107,11 +91,7 @@ Topics published by this stack
|
|||||||
/person/target PoseStamped (camera position, base_link)
|
/person/target PoseStamped (camera position, base_link)
|
||||||
/person/detections Detection2DArray
|
/person/detections Detection2DArray
|
||||||
/cmd_vel Twist (from follower or Nav2)
|
/cmd_vel Twist (from follower or Nav2)
|
||||||
<<<<<<< HEAD
|
|
||||||
/saltybot/cmd String (to ESP32 BALANCE)
|
|
||||||
=======
|
|
||||||
/saltybot/cmd String (to ESP32-S3)
|
/saltybot/cmd String (to ESP32-S3)
|
||||||
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
|
||||||
/saltybot/imu Imu
|
/saltybot/imu Imu
|
||||||
/saltybot/balance_state String
|
/saltybot/balance_state String
|
||||||
"""
|
"""
|
||||||
@ -229,11 +209,7 @@ def generate_launch_description():
|
|||||||
enable_bridge_arg = DeclareLaunchArgument(
|
enable_bridge_arg = DeclareLaunchArgument(
|
||||||
"enable_bridge",
|
"enable_bridge",
|
||||||
default_value="true",
|
default_value="true",
|
||||||
<<<<<<< HEAD
|
|
||||||
description="Launch ESP32 serial bridge + cmd_vel bridge (disable for sim/rosbag)",
|
|
||||||
=======
|
|
||||||
description="Launch ESP32-S3 serial bridge + cmd_vel bridge (disable for sim/rosbag)",
|
description="Launch ESP32-S3 serial bridge + cmd_vel bridge (disable for sim/rosbag)",
|
||||||
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
|
||||||
)
|
)
|
||||||
|
|
||||||
enable_rosbridge_arg = DeclareLaunchArgument(
|
enable_rosbridge_arg = DeclareLaunchArgument(
|
||||||
@ -242,7 +218,7 @@ def generate_launch_description():
|
|||||||
description="Launch rosbridge WebSocket server (port 9090)",
|
description="Launch rosbridge WebSocket server (port 9090)",
|
||||||
)
|
)
|
||||||
|
|
||||||
enable_mission_logging_arg = DeclareLaunchArgument(
|
enable_mission_logging_arg = DeclareLaunchArgument(
|
||||||
"enable_mission_logging",
|
"enable_mission_logging",
|
||||||
default_value="true",
|
default_value="true",
|
||||||
description="Launch ROS2 bag recorder for mission logging (Issue #488)",
|
description="Launch ROS2 bag recorder for mission logging (Issue #488)",
|
||||||
@ -294,11 +270,7 @@ enable_mission_logging_arg = DeclareLaunchArgument(
|
|||||||
esp32_port_arg = DeclareLaunchArgument(
|
esp32_port_arg = DeclareLaunchArgument(
|
||||||
"esp32_port",
|
"esp32_port",
|
||||||
default_value="/dev/esp32-bridge",
|
default_value="/dev/esp32-bridge",
|
||||||
<<<<<<< HEAD
|
|
||||||
description="ESP32 USB CDC serial port",
|
|
||||||
=======
|
|
||||||
description="ESP32-S3 USB CDC serial port",
|
description="ESP32-S3 USB CDC serial port",
|
||||||
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
|
||||||
)
|
)
|
||||||
|
|
||||||
# ── Shared substitution handles ───────────────────────────────────────────
|
# ── Shared substitution handles ───────────────────────────────────────────
|
||||||
@ -318,11 +290,7 @@ enable_mission_logging_arg = DeclareLaunchArgument(
|
|||||||
launch_arguments={"use_sim_time": use_sim_time}.items(),
|
launch_arguments={"use_sim_time": use_sim_time}.items(),
|
||||||
)
|
)
|
||||||
|
|
||||||
<<<<<<< HEAD
|
# ── t=0s ESP32-S3 bidirectional serial bridge ───────────────────────────────
|
||||||
# ── t=0s ESP32 bidirectional serial bridge ────────────────────────────────
|
|
||||||
=======
|
|
||||||
# ── t=0s ESP32-S3 bidirectional serial bridge ────────────────────────────────
|
|
||||||
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
|
||||||
esp32_bridge = GroupAction(
|
esp32_bridge = GroupAction(
|
||||||
condition=IfCondition(LaunchConfiguration("enable_bridge")),
|
condition=IfCondition(LaunchConfiguration("enable_bridge")),
|
||||||
actions=[
|
actions=[
|
||||||
@ -352,11 +320,7 @@ enable_mission_logging_arg = DeclareLaunchArgument(
|
|||||||
],
|
],
|
||||||
)
|
)
|
||||||
|
|
||||||
<<<<<<< HEAD
|
|
||||||
# ── t=2s cmd_vel safety bridge (depends on ESP32 bridge) ────────────────
|
|
||||||
=======
|
|
||||||
# ── t=2s cmd_vel safety bridge (depends on ESP32-S3 bridge) ────────────────
|
# ── t=2s cmd_vel safety bridge (depends on ESP32-S3 bridge) ────────────────
|
||||||
>>>>>>> 291dd68 (feat: remove all STM32/Mamba/BlackPill references — ESP32-S3 only)
|
|
||||||
cmd_vel_bridge = TimerAction(
|
cmd_vel_bridge = TimerAction(
|
||||||
period=2.0,
|
period=2.0,
|
||||||
actions=[
|
actions=[
|
||||||
|
|||||||
@ -1,5 +1,5 @@
|
|||||||
[Unit]
|
[Unit]
|
||||||
Description=CANable 2.0 CAN bus bringup (can0, 500 kbps)
|
Description=CANable 2.0 CAN bus bringup (can0, 1 Mbps DroneCAN — Here4 GPS)
|
||||||
Documentation=https://gitea.vayrette.com/seb/saltylab-firmware/issues/643
|
Documentation=https://gitea.vayrette.com/seb/saltylab-firmware/issues/643
|
||||||
# Wait until the gs_usb net device appears; udev fires After=sys-subsystem-net-devices-can0.device
|
# Wait until the gs_usb net device appears; udev fires After=sys-subsystem-net-devices-can0.device
|
||||||
After=network.target sys-subsystem-net-devices-can0.device
|
After=network.target sys-subsystem-net-devices-can0.device
|
||||||
@ -10,7 +10,7 @@ BindsTo=sys-subsystem-net-devices-can0.device
|
|||||||
Type=oneshot
|
Type=oneshot
|
||||||
RemainAfterExit=yes
|
RemainAfterExit=yes
|
||||||
|
|
||||||
ExecStart=/usr/sbin/ip link set can0 up type can bitrate 500000
|
ExecStart=/usr/sbin/ip link set can0 up type can bitrate 1000000
|
||||||
ExecStop=/usr/sbin/ip link set can0 down
|
ExecStop=/usr/sbin/ip link set can0 down
|
||||||
|
|
||||||
StandardOutput=journal
|
StandardOutput=journal
|
||||||
|
|||||||
@ -2,6 +2,10 @@
|
|||||||
# Exposes the adapter as can0 via the SocketCAN subsystem.
|
# Exposes the adapter as can0 via the SocketCAN subsystem.
|
||||||
# Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/643
|
# Issue: https://gitea.vayrette.com/seb/saltylab-firmware/issues/643
|
||||||
#
|
#
|
||||||
|
# Bitrate is set by can-bringup.service (1 Mbps DroneCAN for Here4 GPS, bd-p47c).
|
||||||
|
# This rule only assigns the interface name and tags it for systemd; it does NOT
|
||||||
|
# bring up the interface — that is handled by can-bringup.service.
|
||||||
|
#
|
||||||
# Install:
|
# Install:
|
||||||
# sudo cp 70-canable.rules /etc/udev/rules.d/
|
# sudo cp 70-canable.rules /etc/udev/rules.d/
|
||||||
# sudo udevadm control --reload && sudo udevadm trigger
|
# sudo udevadm control --reload && sudo udevadm trigger
|
||||||
@ -16,4 +20,4 @@
|
|||||||
SUBSYSTEM=="net", ACTION=="add", \
|
SUBSYSTEM=="net", ACTION=="add", \
|
||||||
ATTRS{idVendor}=="1d50", ATTRS{idProduct}=="606f", \
|
ATTRS{idVendor}=="1d50", ATTRS{idProduct}=="606f", \
|
||||||
NAME="can0", \
|
NAME="can0", \
|
||||||
RUN+="/sbin/ip link set can0 up type can bitrate 500000"
|
TAG+="systemd"
|
||||||
|
|||||||
31
jetson/ros2_ws/src/saltybot_bringup/udev/80-esp32.rules
Normal file
31
jetson/ros2_ws/src/saltybot_bringup/udev/80-esp32.rules
Normal file
@ -0,0 +1,31 @@
|
|||||||
|
# ESP32-S3 USB serial devices (bd-wim1)
|
||||||
|
#
|
||||||
|
# ESP32-S3 BALANCE (Waveshare LCD 1.28) — USB CDC via CH343 USB-UART chip
|
||||||
|
# Appears as /dev/ttyACM0, symlinked to /dev/esp32-balance
|
||||||
|
# idVendor = 1a86 (QinHeng Electronics / WCH)
|
||||||
|
# idProduct = 55d4 (CH343 USB-UART)
|
||||||
|
#
|
||||||
|
# ESP32-S3 IO (bare board JTAG USB) — native USB CDC
|
||||||
|
# Appears as /dev/ttyACM1, symlinked to /dev/esp32-io
|
||||||
|
# idVendor = 303a (Espressif)
|
||||||
|
# idProduct = 1001 (ESP32-S3 USB CDC)
|
||||||
|
#
|
||||||
|
# Install:
|
||||||
|
# sudo cp 80-esp32.rules /etc/udev/rules.d/
|
||||||
|
# sudo udevadm control --reload && sudo udevadm trigger
|
||||||
|
#
|
||||||
|
# Verify:
|
||||||
|
# ls -la /dev/esp32-*
|
||||||
|
# python3 -c "import serial; s=serial.Serial('/dev/esp32-balance', 460800); s.close(); print('OK')"
|
||||||
|
|
||||||
|
# ESP32-S3 BALANCE — CH343 USB-UART (bd-wim1 UART serial bridge)
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="1a86", ATTRS{idProduct}=="55d4", \
|
||||||
|
SYMLINK+="esp32-balance", \
|
||||||
|
TAG+="systemd", \
|
||||||
|
MODE="0660", GROUP="dialout"
|
||||||
|
|
||||||
|
# ESP32-S3 IO — Espressif native USB CDC
|
||||||
|
SUBSYSTEM=="tty", ATTRS{idVendor}=="303a", ATTRS{idProduct}=="1001", \
|
||||||
|
SYMLINK+="esp32-io", \
|
||||||
|
TAG+="systemd", \
|
||||||
|
MODE="0660", GROUP="dialout"
|
||||||
38
jetson/scripts/ros2-launch.sh
Executable file
38
jetson/scripts/ros2-launch.sh
Executable file
@ -0,0 +1,38 @@
|
|||||||
|
#!/usr/bin/env bash
|
||||||
|
# ros2-launch.sh — Source ROS2 Humble + workspace overlay, then exec ros2 launch
|
||||||
|
#
|
||||||
|
# Used by saltybot-*.service units so that ExecStart= does not need to inline
|
||||||
|
# bash source chains.
|
||||||
|
#
|
||||||
|
# Usage (from a service file):
|
||||||
|
# ExecStart=/opt/saltybot/scripts/ros2-launch.sh <pkg> <launch_file> [args...]
|
||||||
|
#
|
||||||
|
# Env vars respected:
|
||||||
|
# ROS_DISTRO default: humble
|
||||||
|
# SALTYBOT_WS default: /opt/saltybot/jetson/ros2_ws/install
|
||||||
|
# ROS_DOMAIN_ID default: 42
|
||||||
|
|
||||||
|
set -euo pipefail
|
||||||
|
|
||||||
|
ROS_DISTRO="${ROS_DISTRO:-humble}"
|
||||||
|
SALTYBOT_WS="${SALTYBOT_WS:-/opt/saltybot/jetson/ros2_ws/install}"
|
||||||
|
|
||||||
|
ROS_SETUP="/opt/ros/${ROS_DISTRO}/setup.bash"
|
||||||
|
WS_SETUP="${SALTYBOT_WS}/setup.bash"
|
||||||
|
|
||||||
|
if [[ ! -f "${ROS_SETUP}" ]]; then
|
||||||
|
echo "[ros2-launch] ERROR: ROS2 setup not found: ${ROS_SETUP}" >&2
|
||||||
|
exit 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
# shellcheck disable=SC1090
|
||||||
|
source "${ROS_SETUP}"
|
||||||
|
|
||||||
|
if [[ -f "${WS_SETUP}" ]]; then
|
||||||
|
# shellcheck disable=SC1090
|
||||||
|
source "${WS_SETUP}"
|
||||||
|
fi
|
||||||
|
|
||||||
|
export ROS_DOMAIN_ID="${ROS_DOMAIN_ID:-42}"
|
||||||
|
|
||||||
|
exec ros2 launch "$@"
|
||||||
@ -1,55 +1,194 @@
|
|||||||
#!/usr/bin/env bash
|
#!/usr/bin/env bash
|
||||||
# install_systemd.sh — Install saltybot systemd services on Orin
|
# install_systemd.sh — Deploy and enable saltybot systemd services on Orin
|
||||||
|
#
|
||||||
# Run as root: sudo ./systemd/install_systemd.sh
|
# Run as root: sudo ./systemd/install_systemd.sh
|
||||||
|
#
|
||||||
|
# What this does:
|
||||||
|
# 1. Deploy repo to /opt/saltybot/jetson
|
||||||
|
# 2. Build ROS2 workspace (colcon)
|
||||||
|
# 3. Install systemd unit files
|
||||||
|
# 4. Install udev rules (CAN, ESP32)
|
||||||
|
# 5. Enable and optionally start all services
|
||||||
|
#
|
||||||
|
# Services installed (start order):
|
||||||
|
# can-bringup.service CANable2 @ 1 Mbps DroneCAN (Here4 GPS)
|
||||||
|
# saltybot-esp32-serial.service ESP32-S3 BALANCE UART bridge (bd-wim1)
|
||||||
|
# saltybot-here4.service Here4 GPS DroneCAN bridge (bd-p47c)
|
||||||
|
# saltybot-ros2.service Full ROS2 stack (perception + nav)
|
||||||
|
# saltybot-dashboard.service Web dashboard on port 8080
|
||||||
|
# saltybot-social.service Social-bot stack (speech + LLM + face)
|
||||||
|
# tailscale-vpn.service Tailscale VPN for remote access
|
||||||
|
#
|
||||||
|
# Prerequisites:
|
||||||
|
# apt install ros-humble-desktop python3-colcon-common-extensions
|
||||||
|
# pip install dronecan (for Here4 GPS node)
|
||||||
|
# usermod -aG dialout orin (for serial port access)
|
||||||
set -euo pipefail
|
set -euo pipefail
|
||||||
|
|
||||||
SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
|
SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
|
||||||
REPO_DIR="$(dirname "${SCRIPT_DIR}")"
|
REPO_DIR="$(dirname "${SCRIPT_DIR}")"
|
||||||
SYSTEMD_DIR="/etc/systemd/system"
|
SYSTEMD_DIR="/etc/systemd/system"
|
||||||
DEPLOY_DIR="/opt/saltybot/jetson"
|
DEPLOY_DIR="/opt/saltybot/jetson"
|
||||||
|
SCRIPTS_DIR="${DEPLOY_DIR}/scripts"
|
||||||
UDEV_DIR="/etc/udev/rules.d"
|
UDEV_DIR="/etc/udev/rules.d"
|
||||||
BRINGUP_SYSTEMD="${REPO_DIR}/ros2_ws/src/saltybot_bringup/systemd"
|
BRINGUP_SYSTEMD="${REPO_DIR}/ros2_ws/src/saltybot_bringup/systemd"
|
||||||
BRINGUP_UDEV="${REPO_DIR}/ros2_ws/src/saltybot_bringup/udev"
|
BRINGUP_UDEV="${REPO_DIR}/ros2_ws/src/saltybot_bringup/udev"
|
||||||
|
WS_SRC="${REPO_DIR}/ros2_ws/src"
|
||||||
|
WS_BUILD="${DEPLOY_DIR}/ros2_ws"
|
||||||
|
|
||||||
|
ROS_DISTRO="${ROS_DISTRO:-humble}"
|
||||||
|
ROS_SETUP="/opt/ros/${ROS_DISTRO}/setup.bash"
|
||||||
|
ORIN_USER="${SALTYBOT_USER:-orin}"
|
||||||
|
|
||||||
log() { echo "[install_systemd] $*"; }
|
log() { echo "[install_systemd] $*"; }
|
||||||
|
warn() { echo "[install_systemd] WARN: $*" >&2; }
|
||||||
|
die() { echo "[install_systemd] ERROR: $*" >&2; exit 1; }
|
||||||
|
|
||||||
[[ "$(id -u)" == "0" ]] || { echo "Run as root"; exit 1; }
|
[[ "$(id -u)" == "0" ]] || die "Run as root (sudo $0)"
|
||||||
|
[[ -f "${ROS_SETUP}" ]] || die "ROS2 ${ROS_DISTRO} not found at ${ROS_SETUP}"
|
||||||
|
|
||||||
# Deploy repo to /opt/saltybot/jetson
|
# ── 1. Deploy repo ─────────────────────────────────────────────────────────────
|
||||||
log "Deploying to ${DEPLOY_DIR}..."
|
log "Deploying repo to ${DEPLOY_DIR}..."
|
||||||
mkdir -p "${DEPLOY_DIR}"
|
mkdir -p "${DEPLOY_DIR}"
|
||||||
rsync -a --exclude='.git' --exclude='__pycache__' \
|
rsync -a \
|
||||||
|
--exclude='.git' \
|
||||||
|
--exclude='__pycache__' \
|
||||||
|
--exclude='*.pyc' \
|
||||||
|
--exclude='.pytest_cache' \
|
||||||
|
--exclude='build/' \
|
||||||
|
--exclude='install/' \
|
||||||
|
--exclude='log/' \
|
||||||
"${REPO_DIR}/" "${DEPLOY_DIR}/"
|
"${REPO_DIR}/" "${DEPLOY_DIR}/"
|
||||||
|
|
||||||
# Install service files
|
# Install launch wrapper script
|
||||||
log "Installing systemd units..."
|
log "Installing ros2-launch.sh..."
|
||||||
cp "${SCRIPT_DIR}/saltybot.target" "${SYSTEMD_DIR}/"
|
install -m 755 "${SCRIPT_DIR}/../scripts/ros2-launch.sh" "/opt/saltybot/scripts/ros2-launch.sh"
|
||||||
cp "${SCRIPT_DIR}/saltybot-social.service" "${SYSTEMD_DIR}/"
|
|
||||||
cp "${SCRIPT_DIR}/tailscale-vpn.service" "${SYSTEMD_DIR}/"
|
|
||||||
cp "${BRINGUP_SYSTEMD}/can-bringup.service" "${SYSTEMD_DIR}/"
|
|
||||||
|
|
||||||
# Install udev rules
|
# ── 2. Build ROS2 workspace ────────────────────────────────────────────────────
|
||||||
|
if command -v colcon &>/dev/null; then
|
||||||
|
log "Building ROS2 workspace (colcon)..."
|
||||||
|
# shellcheck disable=SC1090
|
||||||
|
source "${ROS_SETUP}"
|
||||||
|
(
|
||||||
|
cd "${WS_BUILD}"
|
||||||
|
colcon build \
|
||||||
|
--symlink-install \
|
||||||
|
--cmake-args -DCMAKE_BUILD_TYPE=Release \
|
||||||
|
2>&1 | tee /tmp/colcon-build.log
|
||||||
|
)
|
||||||
|
log "Workspace build complete."
|
||||||
|
else
|
||||||
|
warn "colcon not found — skipping workspace build."
|
||||||
|
warn "Run manually: cd ${WS_BUILD} && colcon build --symlink-install"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# ── 3. Install systemd units ───────────────────────────────────────────────────
|
||||||
|
log "Installing systemd units..."
|
||||||
|
|
||||||
|
# Units from jetson/systemd/
|
||||||
|
for unit in \
|
||||||
|
saltybot.target \
|
||||||
|
saltybot-ros2.service \
|
||||||
|
saltybot-esp32-serial.service \
|
||||||
|
saltybot-here4.service \
|
||||||
|
saltybot-dashboard.service \
|
||||||
|
saltybot-social.service \
|
||||||
|
tailscale-vpn.service
|
||||||
|
do
|
||||||
|
if [[ -f "${SCRIPT_DIR}/${unit}" ]]; then
|
||||||
|
cp "${SCRIPT_DIR}/${unit}" "${SYSTEMD_DIR}/"
|
||||||
|
log " Installed ${unit}"
|
||||||
|
else
|
||||||
|
warn " ${unit} not found in ${SCRIPT_DIR}/ — skipping"
|
||||||
|
fi
|
||||||
|
done
|
||||||
|
|
||||||
|
# Units from saltybot_bringup/systemd/
|
||||||
|
for unit in \
|
||||||
|
can-bringup.service \
|
||||||
|
chromium-kiosk.service \
|
||||||
|
magedok-display.service \
|
||||||
|
salty-face-server.service
|
||||||
|
do
|
||||||
|
if [[ -f "${BRINGUP_SYSTEMD}/${unit}" ]]; then
|
||||||
|
cp "${BRINGUP_SYSTEMD}/${unit}" "${SYSTEMD_DIR}/"
|
||||||
|
log " Installed ${unit} (from bringup)"
|
||||||
|
else
|
||||||
|
warn " ${unit} not found in bringup systemd/ — skipping"
|
||||||
|
fi
|
||||||
|
done
|
||||||
|
|
||||||
|
# ── 4. Install udev rules ──────────────────────────────────────────────────────
|
||||||
log "Installing udev rules..."
|
log "Installing udev rules..."
|
||||||
mkdir -p "${UDEV_DIR}"
|
mkdir -p "${UDEV_DIR}"
|
||||||
cp "${BRINGUP_UDEV}/70-canable.rules" "${UDEV_DIR}/"
|
|
||||||
cp "${BRINGUP_UDEV}/90-magedok-touch.rules" "${UDEV_DIR}/"
|
for rule in \
|
||||||
|
70-canable.rules \
|
||||||
|
80-esp32.rules \
|
||||||
|
90-magedok-touch.rules
|
||||||
|
do
|
||||||
|
if [[ -f "${BRINGUP_UDEV}/${rule}" ]]; then
|
||||||
|
cp "${BRINGUP_UDEV}/${rule}" "${UDEV_DIR}/"
|
||||||
|
log " Installed ${rule}"
|
||||||
|
else
|
||||||
|
warn " ${rule} not found — skipping"
|
||||||
|
fi
|
||||||
|
done
|
||||||
|
|
||||||
udevadm control --reload
|
udevadm control --reload
|
||||||
udevadm trigger --subsystem-match=net --action=add
|
udevadm trigger --subsystem-match=net --action=add
|
||||||
|
udevadm trigger --subsystem-match=tty --action=add
|
||||||
|
log "udev rules reloaded."
|
||||||
|
|
||||||
# Reload and enable
|
# ── 5. Set permissions ─────────────────────────────────────────────────────────
|
||||||
|
log "Ensuring '${ORIN_USER}' is in dialout group (serial port access)..."
|
||||||
|
if id "${ORIN_USER}" &>/dev/null; then
|
||||||
|
usermod -aG dialout "${ORIN_USER}" || warn "usermod failed — add ${ORIN_USER} to dialout manually"
|
||||||
|
else
|
||||||
|
warn "User '${ORIN_USER}' not found — skip usermod"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# ── 6. Reload systemd and enable services ─────────────────────────────────────
|
||||||
|
log "Reloading systemd daemon..."
|
||||||
systemctl daemon-reload
|
systemctl daemon-reload
|
||||||
systemctl enable saltybot.target
|
|
||||||
systemctl enable saltybot-social.service
|
|
||||||
systemctl enable tailscale-vpn.service
|
|
||||||
systemctl enable can-bringup.service
|
|
||||||
|
|
||||||
log "Services installed. Start with:"
|
log "Enabling services..."
|
||||||
log " systemctl start saltybot-social"
|
systemctl enable \
|
||||||
log " systemctl start tailscale-vpn"
|
saltybot.target \
|
||||||
log " systemctl start can-bringup"
|
can-bringup.service \
|
||||||
log " journalctl -fu saltybot-social"
|
saltybot-esp32-serial.service \
|
||||||
log " journalctl -fu tailscale-vpn"
|
saltybot-here4.service \
|
||||||
log " journalctl -fu can-bringup"
|
saltybot-ros2.service \
|
||||||
|
saltybot-dashboard.service \
|
||||||
|
saltybot-social.service \
|
||||||
|
tailscale-vpn.service
|
||||||
|
|
||||||
|
# Enable mosquitto (MQTT broker) if installed
|
||||||
|
if systemctl list-unit-files mosquitto.service &>/dev/null; then
|
||||||
|
systemctl enable mosquitto.service
|
||||||
|
log " Enabled mosquitto.service"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# ── 7. Summary ────────────────────────────────────────────────────────────────
|
||||||
log ""
|
log ""
|
||||||
log "Verify CAN bus: candump can0"
|
log "Installation complete."
|
||||||
log " VESC CAN IDs: 61 (0x3D) and 79 (0x4F)"
|
log ""
|
||||||
|
log "Services will start automatically on next reboot."
|
||||||
|
log "To start now without rebooting:"
|
||||||
|
log " sudo systemctl start saltybot.target"
|
||||||
|
log ""
|
||||||
|
log "Check status:"
|
||||||
|
log " systemctl status can-bringup saltybot-esp32-serial saltybot-here4 saltybot-ros2 saltybot-dashboard"
|
||||||
|
log ""
|
||||||
|
log "Live logs:"
|
||||||
|
log " journalctl -fu can-bringup"
|
||||||
|
log " journalctl -fu saltybot-esp32-serial"
|
||||||
|
log " journalctl -fu saltybot-here4"
|
||||||
|
log " journalctl -fu saltybot-ros2"
|
||||||
|
log " journalctl -fu saltybot-dashboard"
|
||||||
|
log ""
|
||||||
|
log "Dashboard: http://<orin-ip>:8080"
|
||||||
|
log "rosbridge: ws://<orin-ip>:9090"
|
||||||
|
log ""
|
||||||
|
log "Note: saltybot-esp32-serial and saltybot-here4 require packages"
|
||||||
|
log " from bd-wim1 (PR #727) and bd-p47c (PR #728) to be merged."
|
||||||
|
|||||||
38
jetson/systemd/saltybot-dashboard.service
Normal file
38
jetson/systemd/saltybot-dashboard.service
Normal file
@ -0,0 +1,38 @@
|
|||||||
|
[Unit]
|
||||||
|
Description=SaltyBot Web Dashboard (saltybot_dashboard — port 8080)
|
||||||
|
Documentation=https://gitea.vayrette.com/seb/saltylab-firmware
|
||||||
|
#
|
||||||
|
# Serves the live monitoring dashboard on http://<orin-ip>:8080
|
||||||
|
# Subscribes to ROS2 topics over the local DomainID (ROS_DOMAIN_ID=42).
|
||||||
|
# Starts after the ROS2 stack but does not hard-depend on it —
|
||||||
|
# the dashboard handles missing topics gracefully and will show data as
|
||||||
|
# nodes come up.
|
||||||
|
After=network-online.target saltybot-ros2.service
|
||||||
|
Wants=saltybot-ros2.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"
|
||||||
|
|
||||||
|
ExecStart=/opt/saltybot/scripts/ros2-launch.sh \
|
||||||
|
saltybot_dashboard dashboard.launch.py
|
||||||
|
|
||||||
|
Restart=on-failure
|
||||||
|
RestartSec=5s
|
||||||
|
StartLimitInterval=60s
|
||||||
|
StartLimitBurst=5
|
||||||
|
|
||||||
|
TimeoutStartSec=30s
|
||||||
|
TimeoutStopSec=10s
|
||||||
|
|
||||||
|
StandardOutput=journal
|
||||||
|
StandardError=journal
|
||||||
|
SyslogIdentifier=saltybot-dashboard
|
||||||
|
|
||||||
|
[Install]
|
||||||
|
WantedBy=saltybot.target
|
||||||
54
jetson/systemd/saltybot-esp32-serial.service
Normal file
54
jetson/systemd/saltybot-esp32-serial.service
Normal file
@ -0,0 +1,54 @@
|
|||||||
|
[Unit]
|
||||||
|
Description=SaltyBot ESP32-S3 BALANCE UART Serial Bridge (bd-wim1)
|
||||||
|
Documentation=https://gitea.vayrette.com/seb/saltylab-firmware/issues/bd-wim1
|
||||||
|
# Requires package: saltybot_esp32_serial (merged in bd-wim1 → PR #727)
|
||||||
|
#
|
||||||
|
# Publishes:
|
||||||
|
# /saltybot/attitude String JSON (pitch, motor_cmd, vbat_mv, state)
|
||||||
|
# /saltybot/balance_state String
|
||||||
|
# /can/battery BatteryState
|
||||||
|
# /can/vesc/left/state Float32MultiArray [erpm, voltage_v, current_a, temp_c]
|
||||||
|
# /can/vesc/right/state Float32MultiArray
|
||||||
|
# /can/connection_status String
|
||||||
|
#
|
||||||
|
# Subscribes:
|
||||||
|
# /cmd_vel Twist → DRIVE command to ESP32 BALANCE
|
||||||
|
# /estop Bool → ESTOP command
|
||||||
|
# /saltybot/arm Bool → ARM command
|
||||||
|
# /saltybot/pid_update String → PID gains update
|
||||||
|
After=network-online.target
|
||||||
|
# Wait for /dev/esp32-balance (created by 80-esp32.rules udev rule).
|
||||||
|
# TAG+="systemd" in the udev rule makes systemd track dev-esp32\x2dbalance.device.
|
||||||
|
# If device is not present at boot the node's auto-reconnect loop handles it.
|
||||||
|
Wants=network-online.target
|
||||||
|
|
||||||
|
[Service]
|
||||||
|
Type=simple
|
||||||
|
User=orin
|
||||||
|
Group=dialout
|
||||||
|
|
||||||
|
# ROS2 Humble environment + workspace overlay
|
||||||
|
Environment="ROS_DOMAIN_ID=42"
|
||||||
|
Environment="ROS_DISTRO=humble"
|
||||||
|
Environment="SALTYBOT_WS=/opt/saltybot/jetson/ros2_ws/install"
|
||||||
|
|
||||||
|
ExecStart=/opt/saltybot/scripts/ros2-launch.sh \
|
||||||
|
saltybot_esp32_serial esp32_balance.launch.py
|
||||||
|
|
||||||
|
# The node auto-reconnects on serial disconnect (2 s retry).
|
||||||
|
# Restart=on-failure covers node crash; RestartSec gives the device time to re-enumerate.
|
||||||
|
Restart=on-failure
|
||||||
|
RestartSec=5s
|
||||||
|
StartLimitInterval=60s
|
||||||
|
StartLimitBurst=5
|
||||||
|
|
||||||
|
TimeoutStartSec=30s
|
||||||
|
TimeoutStopSec=10s
|
||||||
|
|
||||||
|
# Logging
|
||||||
|
StandardOutput=journal
|
||||||
|
StandardError=journal
|
||||||
|
SyslogIdentifier=saltybot-esp32-serial
|
||||||
|
|
||||||
|
[Install]
|
||||||
|
WantedBy=saltybot.target
|
||||||
50
jetson/systemd/saltybot-here4.service
Normal file
50
jetson/systemd/saltybot-here4.service
Normal file
@ -0,0 +1,50 @@
|
|||||||
|
[Unit]
|
||||||
|
Description=SaltyBot Here4 GPS DroneCAN Bridge (bd-p47c)
|
||||||
|
Documentation=https://gitea.vayrette.com/seb/saltylab-firmware/issues/bd-p47c
|
||||||
|
# Requires package: saltybot_dronecan_gps (merged in bd-p47c → PR #728)
|
||||||
|
# Requires: can0 at 1 Mbps (set by can-bringup.service)
|
||||||
|
#
|
||||||
|
# Publishes:
|
||||||
|
# /gps/fix NavSatFix 5 Hz → navsat_transform EKF
|
||||||
|
# /gps/velocity TwistWithCovarianceStamped 5 Hz
|
||||||
|
# /here4/fix NavSatFix 5 Hz (alias)
|
||||||
|
# /here4/imu Imu 50 Hz
|
||||||
|
# /here4/mag MagneticField 10 Hz
|
||||||
|
# /here4/baro FluidPressure 10 Hz
|
||||||
|
# /here4/status String JSON 1 Hz (node health, fix quality)
|
||||||
|
# /here4/node_id Int32 once (auto-discovered DroneCAN ID)
|
||||||
|
#
|
||||||
|
# Subscribes:
|
||||||
|
# /rtcm ByteMultiArray on demand (RTCM corrections)
|
||||||
|
# /rtcm_hex String on demand (hex fallback)
|
||||||
|
After=network-online.target can-bringup.service
|
||||||
|
Requires=can-bringup.service
|
||||||
|
# If can-bringup stops (CANable2 unplugged), stop this service too
|
||||||
|
BindsTo=can-bringup.service
|
||||||
|
|
||||||
|
[Service]
|
||||||
|
Type=simple
|
||||||
|
User=orin
|
||||||
|
Group=dialout
|
||||||
|
|
||||||
|
Environment="ROS_DOMAIN_ID=42"
|
||||||
|
Environment="ROS_DISTRO=humble"
|
||||||
|
Environment="SALTYBOT_WS=/opt/saltybot/jetson/ros2_ws/install"
|
||||||
|
|
||||||
|
ExecStart=/opt/saltybot/scripts/ros2-launch.sh \
|
||||||
|
saltybot_dronecan_gps here4.launch.py
|
||||||
|
|
||||||
|
Restart=on-failure
|
||||||
|
RestartSec=5s
|
||||||
|
StartLimitInterval=60s
|
||||||
|
StartLimitBurst=5
|
||||||
|
|
||||||
|
TimeoutStartSec=30s
|
||||||
|
TimeoutStopSec=10s
|
||||||
|
|
||||||
|
StandardOutput=journal
|
||||||
|
StandardError=journal
|
||||||
|
SyslogIdentifier=saltybot-here4
|
||||||
|
|
||||||
|
[Install]
|
||||||
|
WantedBy=saltybot.target
|
||||||
59
jetson/systemd/saltybot-ros2.service
Normal file
59
jetson/systemd/saltybot-ros2.service
Normal file
@ -0,0 +1,59 @@
|
|||||||
|
[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
|
||||||
@ -1,8 +1,22 @@
|
|||||||
[Unit]
|
[Unit]
|
||||||
Description=Saltybot Full Stack Target
|
Description=SaltyBot Full Stack Target
|
||||||
Documentation=https://gitea.vayrette.com/seb/saltylab-firmware
|
Documentation=https://gitea.vayrette.com/seb/saltylab-firmware
|
||||||
After=docker.service network-online.target
|
#
|
||||||
Requires=docker.service
|
# Start everything: systemctl start saltybot.target
|
||||||
|
# Stop everything: systemctl stop saltybot.target
|
||||||
|
# Check all: systemctl status 'saltybot-*' can-bringup
|
||||||
|
#
|
||||||
|
# Boot order (dependency chain):
|
||||||
|
# network-online.target
|
||||||
|
# → can-bringup.service (CANable2 @ 1 Mbps DroneCAN)
|
||||||
|
# → saltybot-here4.service (Here4 GPS → /gps/fix, /here4/*)
|
||||||
|
# → saltybot-esp32-serial.service (ESP32-S3 UART → /can/vesc/*, /saltybot/attitude)
|
||||||
|
# → saltybot-ros2.service (full_stack.launch.py, perception + nav)
|
||||||
|
# → saltybot-dashboard.service (port 8080)
|
||||||
|
# (independent) saltybot-social.service
|
||||||
|
# (independent) tailscale-vpn.service
|
||||||
|
After=network-online.target
|
||||||
|
Wants=network-online.target
|
||||||
|
|
||||||
[Install]
|
[Install]
|
||||||
WantedBy=multi-user.target
|
WantedBy=multi-user.target
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user