Skip to main content

Lite 101

A 20-minute hands-on lesson. You'll go from "URDF loaded in RViz" to "the full controller stack running in MuJoCo, with a controller switch under your fingers". By the end you'll recognise the four moving pieces of the project — the URDF, the controller_manager, the mode-FSM controllers, and the simulation backend — and be ready to read the rest of the docs with that mental model in place.

This is a tutorial, not a how-to

The aim here is learning by doing, not "production realism". For calibrating a real robot, recovering from a fault, or wiring a gamepad, look in How-to guides once those land. For the why-behind-the-what, Concepts.

Prerequisites: a built workspace, from the previous page. Every command on this page runs inside pixi shell (one-time per terminal, sources ROS 2 Jazzy + the workspace overlay):

cd bar_ws && pixi shell

Stay in that shell for the rest of the lesson. If you ever want shorter shortcuts (e.g. pixi run launch-mujoco) the equivalent aliases live in How-to → Workspace shortcuts with pixi; the canonical ros2 launch form is what's shown below.

Step 1 — Visualize the URDF

The simplest possible launch: robot_state_publisher + a joint_state_publisher_gui + RViz. No physics, no ros2_control — just the kinematic chain.

ros2 launch bar_description_lite view_lite.launch.py

What you'll see:

  • RViz opens with the chest at world origin and the arms hanging at zero pose.
  • A slider panel (jsp_gui) appears with one slider per actuated joint.
  • Dragging a slider rotates the corresponding link in RViz.
"What is xacro doing?"

The .xacro file is a Jinja-ish macro language for URDFs. The top-level lite.urdf.xacro includes lite.ros2_control.xacro, which selects the <plugin> based on the use_sim / use_fake_hardware args. For RViz visualization we force use_fake_hardware:=true so the <ros2_control> block is harmless (mock_components/GenericSystem, which never gets loaded because RViz doesn't spawn controller_manager).

Close the launch (Ctrl+C in the terminal) before moving on.

Step 2 — Bring up MuJoCo

Now the full control plane against MuJoCo physics: controller_manager hosted inside mujoco_sim, all five mode-FSM controllers loaded, the mode_manager orchestrator running. Nothing on the CAN bus — the MujocoSystem hardware plugin applies the same MIT-mode torque τ = K·(q_cmd − q) + D·(q̇_cmd − q̇) + effort to qfrc_applied that the Robstride firmware computes on silicon.

ros2 launch bar_bringup_lite mujoco.launch.py

A MuJoCo viewer window opens with the Lite humanoid at zero pose. The single mujoco_sim process hosts MuJoCo physics, the MujocoRos2ControlPlugin (loaded as a pluginlib physics plugin), the controller_manager inside that, and the MujocoSystem hardware interface inside that. From the controller's point of view nothing distinguishes this from real hardware — same 5 command interfaces, same 3 state interfaces.

mujoco_sim process

Wait ~2 seconds, then in a second terminal (also inside pixi shell):

ros2 control list_controllers

Expected output (give or take):

joint_state_broadcaster   joint_state_broadcaster/JointStateBroadcaster   active
zero_torque_controller bar/ZeroTorqueController active
damping_controller bar/DampingController inactive
standby_controller bar/StandbyController inactive
rl_policy_controller bar/RLPolicyController inactive
remote_policy_controller bar/RemotePolicyController inactive

What just happened

MuJoCo bringup spawn sequence

zero_torque_controller is active as the safe startup default: it claims all 5 command interfaces on every joint and writes 0 to all of them every tick. From an operator's perspective the robot is "alive but inert".

The four other controllers are loaded but inactive. Loading them runs their on_configure (params parsed, publishers/subscribers created) without claiming the command interfaces. They sit ready to be activated in a single service call.

Watch the topics

ros2 topic list | grep -E "joint_states|control_mode|standby|safety"
# /control_mode
# /lite/joint_states
# /safety_status
# /standby_controller/state

joint_state_broadcaster is remapped at bringup so that it publishes on /lite/joint_states (the owner-prefixed topic) rather than the global /joint_states. The controller_manager's update rate is 200 Hz in MuJoCo, 50 Hz on real hardware:

ros2 topic hz /lite/joint_states
# average rate: 200.000

mode_manager publishes /control_mode (the current FSM state) at 50 Hz:

ros2 topic echo --once /control_mode
# mode: 0 # ZERO_TORQUE
# controller_name: zero_torque_controller
# status_message: ''
"See it move"

Two interchangeable live visualizers ride on /lite/joint_states + /robot_description, both shipped by bar_bringup_lite. On the tethered deployment they live on the operator workstation (host side of the tether), spawned by viz.launch.py:

ros2 launch bar_bringup_lite viz.launch.py                  # viser, http://localhost:8080
ros2 launch bar_bringup_lite viz.launch.py viewer:=rerun # native rerun window

For a single-machine MuJoCo run, the standalone shortcuts work too — they auto-discover /robot_description and the joint-state topic on the local domain:

ros2 run bar_bringup_lite viser_viz
ros2 run bar_bringup_lite rerun_viz

Visualiser dependencies (rerun-sdk, viser, yourdfpy, scipy) ship in the pixi env. See How-to → Live visualization and Concepts → Architecture → Deployment topology.

Step 3 — Trigger a mode transition

The whole project is built around mode transitions: the operator (or a fault) requests an intent, mode_manager resolves it to a controller switch, and the controller_manager swaps the active controller. For this lesson we'll just call the controller_manager service directly to simulate what mode_manager would have done in response to the gamepad X (DAMP) intent.

ros2 control switch_controllers \
--activate damping_controller \
--deactivate zero_torque_controller

Verify:

ros2 control list_controllers
# damping_controller bar/DampingController active
# zero_torque_controller bar/ZeroTorqueController inactive
Why DAMPING is the "compliant fail-safe"

With stiffness K = 0 there's no position-restoring force. With damping D nonzero the joint resists velocity. The result: the robot is soft under gravity (push the arm and it moves) but damped (it doesn't oscillate). This is the state you transition into before powering down, before swapping a tool, or after any non-OK SafetyStatus. See Concepts → Five-mode FSM.

If gravity is on (it is by default in our MJCF) and you switched to DAMPING after a few seconds in ZERO_TORQUE, the arms in the MuJoCo viewer should now sag and settle rather than freely flopping — the damping resists fall velocity but the zero stiffness can't hold them up. That contrast between the two modes is the lesson of this step.

Step 4 — Switch back, then exit

Always end a session in a known safe state. Switch back to ZERO_TORQUE, which makes the motors fully compliant again:

ros2 control switch_controllers \
--activate zero_torque_controller \
--deactivate damping_controller

Then Ctrl+C the launch terminal. The plugin's on_deactivate runs, sending Disable to every joint (no-op in MuJoCo but matters on silicon), and mujoco_sim shuts down cleanly.

What you just saw

Four moving pieces, all worth recognising for the rest of the docs:

PieceWhat it does
URDF (bar_description_lite)Kinematic + dynamic description. Same file across mock / sim / real — the <ros2_control> <plugin> is the only difference.
controller_managerHosts the hardware plugin + every controller. The "tick loop" of the system. Update rate 50 Hz here.
Mode-FSM controllers (bar_controllers)Five plugins, one active at a time. zero_torque (safe default), damping (compliant fail-safe), standby (interpolate to a pose), rl_policy (in-process ONNX), remote_policy (out-of-process Python).
MuJoCo / Robstride (the simulation / real backend)Where the MIT torque actually gets applied. Same five command interfaces in both.

Next

Where to go from here, depending on what you want: