Implements UART bridge verification between Flight Controller (STM32F722) and Jetson Orin. Changes: 1. jetson/scripts/uart_test.py (12.7 KB) - Opens /dev/ttyTHS1 at 921600 baud - Sends jlink binary test frames (PING, VERSION, ECHO) - Verifies CRC16-CCITT frame integrity - Logs transactions with timestamps - JSON result export and optional MQTT publishing 2. jetson/ros2_ws/src/saltybot_bridge/launch/uart_bridge.launch.py - ROS2 launch file for serial_bridge_node on UART port - Configurable port (default /dev/ttyTHS1), baud rate (921600) - Bridges FC telemetry to /saltybot/imu, /saltybot/balance_state - Publishes diagnostics to /diagnostics Usage: Test: sudo python3 jetson/scripts/uart_test.py Launch: ros2 launch saltybot_bridge uart_bridge.launch.py Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
84 lines
3.2 KiB
Python
84 lines
3.2 KiB
Python
"""
|
||
uart_bridge.launch.py — FC↔Orin UART bridge (Issue #362)
|
||
|
||
Launches serial_bridge_node configured for Jetson Orin UART port.
|
||
Bridges Flight Controller (STM32F722) 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 THS0–THS3):
|
||
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
|
||
- STM32 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 (THS0–THS3)",
|
||
),
|
||
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"),
|
||
},
|
||
],
|
||
),
|
||
])
|