sl-webui 28c934deff feat(arch): migrate all STM32/Mamba/BlackPill refs to ESP32 BALANCE/IO + fix roslib@1.4.0
Architecture change (2026-04-03): Mamba F722S (STM32F722) and BlackPill
replaced by ESP32 BALANCE (PID loop) and ESP32 IO (motors/sensors/comms).

- Update CLAUDE.md, docs, chassis BOM/ASSEMBLY, pinout, power-budget,
  wiring-diagram, TEAM.md, AUTONOMOUS_ARMING.md, docker-compose
- Update all ROS2 package comments, config labels, launch args
  (stm32_port→esp32_port, /dev/stm32-bridge→/dev/esp32-bridge)
- Update WebUI: stm32Mode→esp32Mode, stm32Version→esp32Version,
  "STM32 State/Mode" labels → "ESP32 State/Mode" (ControlMode, SettingsPanel)
- Add TODO(esp32-migration) markers on stm32_protocol.py and mamba_protocol.py
  binary frame layouts — pending ESP32 protocol spec from max
- Fix roslib CDN 1.3.0→1.4.0 in all 11 HTML panels (fixes ROS2 Humble
  rosbridge "Received a message without an op" incompatibility)

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-04-03 23:09:10 -04:00

84 lines
3.2 KiB
Python
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

"""
uart_bridge.launch.py — FC↔Orin UART bridge (Issue #362)
Launches serial_bridge_node configured for Jetson Orin UART port.
Bridges Flight Controller (ESP32) telemetry from /dev/ttyTHS1 into ROS2.
Published topics (same as USB CDC bridge):
/saltybot/imu sensor_msgs/Imu — pitch/roll/yaw as angular velocity
/saltybot/balance_state std_msgs/String (JSON) — full PID diagnostics
/diagnostics diagnostic_msgs/DiagnosticArray — system health
Usage:
ros2 launch saltybot_bridge uart_bridge.launch.py
# Override UART port (Orin has THS0THS3):
ros2 launch saltybot_bridge uart_bridge.launch.py uart_port:=/dev/ttyTHS0
# Override baud rate:
ros2 launch saltybot_bridge uart_bridge.launch.py baud_rate:=115200
Prerequisites:
- Flight Controller connected to /dev/ttyTHS1 @ 921600 baud
- ESP32 BALANCE firmware transmitting JSON telemetry frames (50 Hz)
- ROS2 environment sourced (source install/setup.bash)
Note:
/dev/ttyTHS1 is the native UART1 on Jetson Orin. Verify connectivity:
$ cat /dev/ttyTHS1 | head -5
{"p":123,"r":-45,"e":0,"ig":0,"m":0,"s":1,"y":0}
...
Troubleshooting:
- "Permission denied" → run with sudo or add user to dialout group
- No frames received → check Flight Controller baud rate, verify UART cable
- Garbled output → check baud rate mismatch, check cable shield/termination
"""
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
# ── Launch arguments ───────────────────────────────────────────────────
DeclareLaunchArgument(
"uart_port",
default_value="/dev/ttyTHS1",
description="Jetson Orin UART device (THS0THS3)",
),
DeclareLaunchArgument(
"baud_rate",
default_value="921600",
description="Serial baud rate (Flight Controller standard)",
),
DeclareLaunchArgument(
"timeout",
default_value="0.1",
description="Serial read timeout in seconds",
),
DeclareLaunchArgument(
"reconnect_delay",
default_value="2.0",
description="Delay before reconnect attempt on serial error (seconds)",
),
# ── Serial bridge node ─────────────────────────────────────────────────
Node(
package="saltybot_bridge",
executable="serial_bridge_node",
name="fc_uart_bridge",
output="screen",
parameters=[
{
"serial_port": LaunchConfiguration("uart_port"),
"baud_rate": LaunchConfiguration("baud_rate"),
"timeout": LaunchConfiguration("timeout"),
"reconnect_delay": LaunchConfiguration("reconnect_delay"),
},
],
),
])