Skip to main content

Topics & services

Index of the ROS topics and services that bar_ros2 publishes, subscribes, or serves. Use this page to find "who publishes X" or "what topic carries Y".

Topics

Always-on (any bringup)

TopicTypeQoSPublisherNotes
/lite/joint_statessensor_msgs/JointStateRELIABLE depth 10joint_state_broadcaster (remapped at bringup)Position/velocity/effort in joint frame (post-calibration). Owner-prefixed — there is no global /joint_states. 50 Hz real, 200 Hz sim.
/imu/datasensor_msgs/ImuRELIABLEIMU driverSubscribed by RemotePolicyController and bar_policy.
/robot_descriptionstd_msgs/StringRELIABLE TRANSIENT_LOCAL depth 1robot_state_publisherURDF XML. Latched — subscribers can join any time.
/tf, /tf_statictf2_msgs/TFMessageRELIABLErobot_state_publisherKinematic chain from /lite/joint_states.
/clockrosgraph_msgs/ClockRELIABLEmujoco_sim (sim only)Sim-time on the MuJoCo path. Every other node consumes when use_sim_time:=true.

Bringup-dependent

TopicTypeQoSPublisherWhen present
/control_modebar_msgs/ControlModeRELIABLE depth 10mode_managerWhen enable_mode_manager:=true (default for real.launch.py / mujoco.launch.py). 50 Hz.
/safety_statusbar_msgs/SafetyStatusRELIABLE TRANSIENT_LOCAL depth 1every hardware pluginPer-bus (bar_robstride/can0, bar_robstride/can1 for Lite). Published only on change.
/standby_controller/statebar_msgs/StandbyStateRELIABLE TRANSIENT_LOCAL depth 1bar/StandbyController (when active)Carries is_finished — the gate for START_* intents.
/joysensor_msgs/JoySENSOR_DATAjoy_nodeWhen enable_gamepad:=true (default). The launch hard-fails on missing /dev/input/js*.

Active-controller-dependent

TopicTypeQoSDirectionWhen
/remote_policy_controller/commandbar_msgs/MITCommandRELIABLE depth 4subscribed by RemotePolicyControllerWhen RemotePolicyController is active. Published by bar_policy/remote_policy_runner (or its pianist_policy.PianoPolicyRunner subclass).
/piano/key_statepianist_msgs/PianoKeyStateRELIABLE KEEP_LAST(1)sim: pianist_policy/piano_state_bridge; real: pianist_policy/midi_keyboard_driverPiano runs. Measured key state.
/piano/target_keyspianist_msgs/PianoKeyStateRELIABLE KEEP_LAST(1)pianist_policy/PianoPolicyRunner._tickPiano runs. Song's goal frame, re-published every tick for bag-based metrics.
/forward_mit_controller/commandsstd_msgs/Float64MultiArrayRELIABLE depth 10subscribed by upstream forward_command_controller/MultiInterfaceForwardCommandControllerUsed by mit_slider_gui.

/parameter_events and friends

Every node (controllers, mode_manager, plugins) publishes the standard ROS infrastructure topics:

  • /parameter_events, /rosout
  • ~/get_parameters, ~/set_parameters, etc. (per node)

These are conventional ROS — not specific to bar_ros2. Mentioned here so ros2 topic list output isn't confusing.

Services

mode_manager FSM-transition services

std_srvs/Trigger services. Same intents as the gamepad — for use on keyboardless lab boxes or scripted tests.

ServiceEffect
/bar/mode/damp→ DAMPING from any state
/bar/mode/loadDAMPING → STANDBY
/bar/mode/start_remoteSTANDBY → REMOTE (gated on is_finished)
/bar/mode/start_locomotionSTANDBY → LOCOMOTION (gated on is_finished)
/bar/mode/quitexit (only from ZERO_TORQUE or DAMPING)

controller_manager-side (under /controller_manager)

Standard controller_manager services. Useful ones:

ServiceTypePurpose
/controller_manager/list_controllerscontroller_manager_msgs/ListControllersWhat's loaded, active state per controller
/controller_manager/list_hardware_componentscontroller_manager_msgs/ListHardwareComponentsWhich <ros2_control> blocks are active
/controller_manager/load_controllercontroller_manager_msgs/LoadControllerBacking for ros2 control load_controller
/controller_manager/switch_controllercontroller_manager_msgs/SwitchControllerBacking for ros2 control switch_controllers
/controller_manager/configure_controllercontroller_manager_msgs/ConfigureControllerForce on_configure

mode_manager is a client of /controller_manager/switch_controller (async, STRICT). You can call it directly from ros2 control for operator-driven debug — see How-to → Switch without the FSM.

Per-node services (parameter handling)

Every node hosts the standard rclcpp parameter services:

  • ~/get_parameters, ~/set_parameters, ~/list_parameters, etc.

rqt_reconfigure is a generic frontend for these.

QoS reference

Used in the tables above:

QoS profileReliabilityDurabilityHistoryWhen
RELIABLE (default)RELIABLEVOLATILEKEEP_LAST 10Most topics
SENSOR_DATABEST_EFFORTVOLATILEKEEP_LAST 5High-rate sensors — IMU, joy
TRANSIENT_LOCALRELIABLETRANSIENT_LOCALKEEP_LAST 1Latched — late subscribers see the most-recent value (URDF, SafetyStatus, StandbyState)

If a publisher's QoS doesn't match a subscriber's, ROS may silently drop messages. The TRANSIENT_LOCAL combo is the most common mismatch source — subscribers must also request TRANSIENT_LOCAL durability to receive the latched value.

Inspecting at runtime

From a sourced workspace env (cd bar_ws && pixi shell):

# What's published right now?
ros2 topic list

# Who's publishing X?
ros2 topic info /control_mode --verbose

# What's the QoS?
ros2 topic info /safety_status --verbose

# Recent rate
ros2 topic hz /lite/joint_states

# What service does X expose?
ros2 service list | grep mode_manager
ros2 service info /controller_manager/switch_controller

See also