"""stm32_cmd.launch.py — Launch the binary-framed STM32 command node (Issue #119). Usage: # Default (binary protocol, bidirectional): ros2 launch saltybot_bridge stm32_cmd.launch.py # Override serial port: ros2 launch saltybot_bridge stm32_cmd.launch.py serial_port:=/dev/ttyACM1 # Custom velocity scales: ros2 launch saltybot_bridge stm32_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", "stm32_cmd_params.yaml") return LaunchDescription([ DeclareLaunchArgument("serial_port", default_value="/dev/ttyACM0"), DeclareLaunchArgument("baud_rate", default_value="921600"), DeclareLaunchArgument("speed_scale", default_value="1000.0"), DeclareLaunchArgument("steer_scale", default_value="-500.0"), DeclareLaunchArgument("watchdog_timeout", default_value="0.5"), 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"), "speed_scale": LaunchConfiguration("speed_scale"), "steer_scale": LaunchConfiguration("steer_scale"), "watchdog_timeout": LaunchConfiguration("watchdog_timeout"), "heartbeat_period": LaunchConfiguration("heartbeat_period"), }, ], ), ])