sl-jetson da6a17cdcb feat: ROS2 gimbal control node (Issue #548)
saltybot_gimbal ROS2 Python package for pan/tilt camera head control
via JLINK binary protocol over serial to STM32 (Issue #547 C side).

- gimbal_node.py: subscribes /saltybot/gimbal/cmd (Vector3: pan, tilt,
  speed), publishes /saltybot/gimbal/state (JSON), /saltybot/gimbal/cmd_echo
- Services: /saltybot/gimbal/home (Trigger), /saltybot/gimbal/look_at
  (Trigger + /saltybot/gimbal/look_at_target PointStamped)
- jlink_gimbal.py: JLINK codec matching jlink.h — CMD_GIMBAL_POS=0x0B,
  TLM_GIMBAL_STATE=0x84, CRC16-CCITT, deg*10 encoding, speed register
- MotionAxis: trapezoidal velocity profile (configurable accel + speed)
- Configurable limits: pan ±150°, tilt ±45° (gimbal_params.yaml)
- Serial reconnect with configurable retry delay
- 48 unit tests — all passing

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

51 lines
1.5 KiB
Python

"""gimbal.launch.py — Launch saltybot_gimbal node (Issue #548)."""
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_gimbal")
serial_port_arg = DeclareLaunchArgument(
"serial_port",
default_value="/dev/ttyTHS1",
description="JLINK serial port to STM32",
)
pan_limit_arg = DeclareLaunchArgument(
"pan_limit_deg",
default_value="150.0",
description="Pan soft limit ± degrees",
)
tilt_limit_arg = DeclareLaunchArgument(
"tilt_limit_deg",
default_value="45.0",
description="Tilt soft limit ± degrees",
)
gimbal_node = Node(
package="saltybot_gimbal",
executable="gimbal_node",
name="gimbal_node",
output="screen",
parameters=[
os.path.join(pkg, "config", "gimbal_params.yaml"),
{
"serial_port": LaunchConfiguration("serial_port"),
"pan_limit_deg": LaunchConfiguration("pan_limit_deg"),
"tilt_limit_deg": LaunchConfiguration("tilt_limit_deg"),
},
],
)
return LaunchDescription([
serial_port_arg,
pan_limit_arg,
tilt_limit_arg,
gimbal_node,
])