ROS 2 Platform API
note
Motor topic message types may differ based on the motor controller used by the platform.
Platform Topics
Topic | Message type | Publisher | Description | QoS | Platform |
---|---|---|---|---|---|
cmd_vel | geometry_msgs/TwistStamped | User | Commands the robot to drive at a velocity | System Default | All |
diagnostics | diagnostics_msgs/DiagnosticArray | Various nodes | Diagnostic messages reported by various nodes | System Default | All |
joy_teleop/cmd_vel | geometry_msgs/TwistStamped | Joy node | Velocity commands from joystick inputs | System Default | All |
joy_teleop/joy | sensor_msgs/Joy | Joy node | Joystick input states | System Default | All |
platform/bms/state | sensor_msgs/BatteryState | Battery node | System battery state | Sensor Data | All |
platform/cmd_fans | clearpath_platform_msgs/Fans | User | User fans command request | System Default | A300 |
platform/cmd_lights | clearpath_platform_msgs/Lights | User | User lighting command request | System Default | A300, DX100, DX150, R100 |
platform/cmd_vel | geometry_msgs/TwistStamped | Twist Mux node | Resulting velocity commands from twist mux | System Default | All |
platform/dynamic_joint_states | control_msgs/DynamicJointState | Control node | Platform dynamic joint state | System Default | All |
platform/emergency_stop | std_msgs/Bool | MCU node | State of platform emergency stop | Sensor Data | All |
platform/joint_states | sensor_msgs/JointState | Control node | Platform joint state | System Default | All |
platform/motors/cmd | clearpath_platform_msgs/Drive sensor_msgs/JointState | Control node | Command velocities to individual wheels | Sensor Data | All |
platform/motors/feedback | clearpath_platform_msgs/DriveFeedback clearpath_motor_msgs/LynxMultiFeedback clearpath_motor_msgs/PumaMultiFeedback | MCU or Motor Driver node | Feedback from motor drive unit | Sensor Data | All |
platform/motors/status | clearpath_motor_msgs/LynxMultiStatus clearpath_motor_msgs/PumaMultiStatus | Motor Driver node | Status from motor drive unit | Sensor Data | A300, DX100, DX150, R100 |
platform/odom | nav_msgs/Odometry | Control node | Platform wheel odometry | System Default | All |
platform/odom/filtered | nav_msgs/Odometry | EKF node | Platform wheel odometry fused with IMU data | System Default | All |
platform/wifi_connected | std_msgs/Bool | Wireless Watcher node | Wi-Fi connected status | System Default | All |
platform/wifi_status | wireless_msgs/Connection | Wireless Watcher node | Wi-Fi signal status | System Default | All |
robot_description | std_msgs/String | Robot State Publisher | Robot description | Transient Local | All |
tf | tf2_msgs/TFMessage | Various nodes | Link transforms | System Default | All |
tf_static | tf2_msgs/TFMessage | Various nodes | Static link transforms | Transient Local | All |
twist_marker_server/cmd_vel | geometry_msgs/TwistStamped | Twist Marker Server | Velocity commands from twist marker | System Default | All |
/rosout | rcl_interfaces/Log | Various nodes | System Logs | Transient Local | All |
Platform Actions
Service | Service type | Server | Description | QoS | Platform |
---|---|---|---|---|---|
platform/motors/calibrate | clearpath_motor_msgs/LynxCalibrate | Lynx Motor Node | Calibrate Lynx motor controllers | System default | A300 |
platform/motors/update | clearpath_motor_msgs/LynxUpdate | Lynx Motor Node | Update Lynx motor controllers | System default | A300 |
Platform Services
Service | Service type | Server | Description | QoS | Platform |
---|---|---|---|---|---|
platform/pinout/aux_# | clearpath_platform_msgs/SetPinout | Pinout control node | Set auxiliary output pin state to on/off/toggle | System default | A300, DX100, DX150 |
platform/pinout/gpo_# | clearpath_platform_msgs/SetPinout | Pinout control node | Set general purpose output pin state to on/off/toggle | System default | A300 |
platform/pinout/user_pwr_ctrl | std_srvs/SetBool | Pinout control node | Set user power rail output to on/off | System default | A300 |