sl-uwb bb35ddd56d chore: resolve git conflict markers and complete legacy STM32/Mamba → ESP32-S3 rename
- Resolve 73 committed conflict markers (bulk resolution taking theirs/ESP32 side)
- Rename all MAMBA_CMD_* → BALANCE_CMD_*, MAMBA_TELEM_* → BALANCE_TELEM_*
- Rename FC_STATUS/VESC/IMU/BARO → BALANCE_STATUS/VESC/IMU/BARO in protocol_defs.py
- Update can_bridge_node.py: fix imports, replace legacy encode/decode calls with
  balance_protocol equivalents (encode_velocity_cmd, encode_mode_cmd, decode_imu_telem,
  decode_battery_telem, decode_vesc_state); fix watchdog and destroy_node
- Rename stm32_protocol.py/stm32_cmd_node.py → esp32_protocol.py/esp32_cmd_node.py
- Delete mamba_protocol.py; stm32_cmd.launch.py/stm32_cmd_params.yaml archived
- Update can_bridge_params.yaml: mamba_can_id → balance_can_id
- Update docs/AGENTS.md, SALTYLAB.md, wiring-diagram.md for ESP32-S3 architecture
- Update test/test_ota.py sys.path to legacy/stm32/scripts/flash_firmware.py
- No legacy STM32/Mamba refs remain outside legacy/ and SAUL-TEE-SYSTEM-REFERENCE.md

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-04-04 09:11:24 -04:00

46 lines
1.6 KiB
Python

"""esp32_cmd.launch.py — Launch the binary-framed ESP32-S3 command node (Issue #119).
Usage:
# Default (binary protocol, bidirectional):
ros2 launch saltybot_bridge esp32_cmd.launch.py
# Override serial port:
ros2 launch saltybot_bridge esp32_cmd.launch.py serial_port:=/dev/ttyACM1
# Custom velocity scales:
ros2 launch saltybot_bridge esp32_cmd.launch.py speed_scale:=800.0 steer_scale:=-400.0"""
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", "esp32_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="esp32_cmd_node",
name="esp32_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"),
},
],
),
])