Update CAN and serial bridge code to match authoritative protocol spec from docs/SAUL-TEE-SYSTEM-REFERENCE.md §5-6 (hal, 2026-04-04). mamba_protocol.py (CAN, Orin ↔ ESP32 BALANCE): - 0x300 DRIVE: [speed:i16][steer:i16][mode:u8][flags:u8][_:u16] — combined frame - 0x301 ARM: [arm:u8] - 0x302 PID: [kp:f16][ki:f16][kd:f16][_:u16] — half-float gains - 0x303 ESTOP: [0xE5] — magic byte cut - 0x400 ATTITUDE: [pitch:f16][speed:f16][yaw_rate:f16][state:u8][flags:u8] - 0x401 BATTERY: [vbat_mv:u16][fault_code:u8][rssi:i8] - Add VESC STATUS1/4/5 decode helpers; VESC IDs 56 (left) / 68 (right) can_bridge_node.py: - /cmd_vel → encode_drive_cmd (speed/steer int16, MODE_DRIVE) - /estop → encode_estop_cmd (magic 0xE5); clear → DISARM - /saltybot/arm → encode_arm_cmd (new subscription) - Watchdog sends DRIVE(0,0,MODE_IDLE) when /cmd_vel silent - ATTITUDE (0x400) → /saltybot/attitude + /saltybot/balance_state JSON - BATTERY (0x401) → /can/battery BatteryState - VESC STATUS1 frames → /can/vesc/left|right/state stm32_cmd_node.py — rewritten for inter-board protocol API: - Imports from updated stm32_protocol (BAUD_RATE=460800, new frame types) - RX: RcChannels → /saltybot/rc_channels, SensorData → /saltybot/sensors - TX: encode_led_cmd, encode_output_cmd from /saltybot/leds + /saltybot/outputs - HEARTBEAT (0x20) timer replaces old SPEED_STEER/ARM logic stm32_cmd_params.yaml: serial_port=/dev/esp32-io, baud=460800 stm32_cmd.launch.py: updated defaults and description Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
47 lines
1.7 KiB
Python
47 lines
1.7 KiB
Python
"""stm32_cmd.launch.py — Launch the ESP32-S3 IO auxiliary bridge node.
|
|
|
|
Connects to ESP32-S3 IO board via USB-CDC @ 460800 baud (inter-board protocol).
|
|
Handles RC monitoring, sensor data, LED/output commands.
|
|
Primary drive path uses CAN (can_bridge_node / saltybot_can_node), not this node.
|
|
|
|
Spec: docs/SAUL-TEE-SYSTEM-REFERENCE.md §5
|
|
|
|
Usage:
|
|
ros2 launch saltybot_bridge stm32_cmd.launch.py
|
|
ros2 launch saltybot_bridge stm32_cmd.launch.py serial_port:=/dev/ttyACM0
|
|
"""
|
|
|
|
import os
|
|
from ament_index_python.packages import get_package_share_directory
|
|
from launch import LaunchDescription
|
|
from launch.actions import DeclareLaunchArgument
|
|
from launch.substitutions import LaunchConfiguration
|
|
from launch_ros.actions import Node
|
|
|
|
|
|
def generate_launch_description() -> LaunchDescription:
|
|
pkg = get_package_share_directory("saltybot_bridge")
|
|
params_file = os.path.join(pkg, "config", "stm32_cmd_params.yaml")
|
|
|
|
return LaunchDescription([
|
|
DeclareLaunchArgument("serial_port", default_value="/dev/esp32-io"),
|
|
DeclareLaunchArgument("baud_rate", default_value="460800"),
|
|
DeclareLaunchArgument("heartbeat_period", default_value="0.2"),
|
|
|
|
Node(
|
|
package="saltybot_bridge",
|
|
executable="stm32_cmd_node",
|
|
name="stm32_cmd_node",
|
|
output="screen",
|
|
emulate_tty=True,
|
|
parameters=[
|
|
params_file,
|
|
{
|
|
"serial_port": LaunchConfiguration("serial_port"),
|
|
"baud_rate": LaunchConfiguration("baud_rate"),
|
|
"heartbeat_period": LaunchConfiguration("heartbeat_period"),
|
|
},
|
|
],
|
|
),
|
|
])
|