Skip to main content

Messages

Custom ROS 2 interfaces. Frozen once a trained policy depends on the schema (changing the layout forces retraining). bar_msgs ships four messages and pianist_msgs (sibling repo, piano task) ships one.

Topology

bar_msgs pub/sub topology

bar_msgs/MITCommand

The command format sent from any out-of-process policy to RemotePolicyController. Mirrors the five MIT-mode command interfaces one-to-one.

std_msgs/Header header
string[] joint_names # validated against the controller's claimed order
float64[] position
float64[] velocity
float64[] effort
float64[] stiffness
float64[] damping

All arrays must have the same length as joint_names. The controller rejects the message if the order doesn't match its joints: parameter.

Why all five fields, every message

Sending only position (Cartesian-style) would force the receiver to assume defaults for the rest. By making the policy send all five, the intent is explicit: a "position-only" command would still send velocity=0, stiffness=Kp_target, damping=Kd_target, effort=0 — making the controller re-creation fully reproducible.

bar_msgs/ControlMode

Mode-FSM telemetry, published by mode_manager at tick rate (50 Hz).

std_msgs/Header header

uint8 ZERO_TORQUE = 0
uint8 DAMPING = 1
uint8 STANDBY = 2
uint8 LOCOMOTION = 3
uint8 REMOTE = 4

uint8 mode
string controller_name # spawned controller name (e.g. "damping_controller")
string status_message # human-readable, may carry rejection reason

The numeric mode field uses the explicit constants above. Consumers should match against the uint8 <name> = <value> defines, not hard-code integers.

bar_msgs/StandbyState

Published by StandbyController on ~/state (which resolves to /standby_controller/state) with TRANSIENT_LOCAL (latched) QoS so a late-joining mode_manager immediately sees the most recent value.

std_msgs/Header header
uint32 current_segment # index into the pose sequence
uint32 total_segments
float64 progress # [0, 1] within the current segment
bool is_finished # true once final pose + final gains reached

mode_manager gates the START intent (STANDBY → LOCOMOTION/REMOTE) on is_finished == true.

bar_msgs/SafetyStatus

Layered safety telemetry. Any hardware plugin or controller may publish; the flags bitmask is plugin-specific.

std_msgs/Header header

uint8 OK = 0
uint8 WARNING = 1 # degraded but commands still honored
uint8 FAULT = 2 # commands no longer guaranteed; transition recommended
uint8 CRITICAL = 3 # immediate fault fallback required

uint8 level
string source # e.g. "bar_robstride/can0", "rl_policy_controller"
uint32 flags # plugin-specific bitmask
string message

Bit layout (see Concepts → Safety pipeline for the per-flag detection logic):

BitConstantMeaning
0FLAG_BUS_OFFKernel CAN socket couldn't open or returned ENETDOWN. Sticky until on_activate.
1FLAG_RX_TIMEOUTOne or more joints stopped reporting status frames within rx_timeout_ms.
2FLAG_TX_QUEUE_OVERRUNOutbound SPSC ring overflowed.
3FLAG_MOTOR_FAULTA Robstride status frame reported a non-OK motor state.
4FLAG_TEMPERATURE_LIMITA motor exceeded its overtemperature threshold.
5FLAG_INVALID_FRAMEA frame on the bus had the wrong comm-type code or DLC.

pianist_msgs/PianoKeyState

Piano-key state. Defined in the pianist_msgs package (sibling repo pianist_ros2, not bar_ros2). The same schema is reused on two topics:

  • /piano/key_statemeasured key state. Published by pianist_policy/piano_state_bridge in sim and pianist_policy/midi_keyboard_driver on real hardware. RELIABLE + KEEP_LAST(1).
  • /piano/target_keys — the song's goal frame, re-published every tick by pianist_policy.PianoPolicyRunner._tick so a bag containing the two topics is sufficient for offline F1/precision/recall via pianist_metrics. RELIABLE + KEEP_LAST(1).
std_msgs/Header header
bool[] pressed # length 88; pressed[i]==true iff key i is activated

The sim-side publisher (piano_state_bridge) binarises against KEY_TRIGGER_THRESHOLD = 0.70 (matching upstream T-K-233/Robot-Descriptions/robot_descriptions/piano/consts.py).