Skip to main content

Launch args

Every BAR bringup follows the same vocabulary. Each robot ships two parallel launchesreal.launch.py for silicon, mujoco.launch.py for MuJoCo physics. Operators pick the launch file rather than flipping a use_fake_hardware flag on a single one. The xacro still accepts use_fake_hardware:=true for direct ad-hoc visualization, but no bundled launch enables that path.

Launches live in two repos:

  • bar_ros2 ships the Lite + Prime control-plane bringups (bar_bringup_lite, bar_bringup_prime), the URDF inspector (bar_description_lite), and the generic ONNX policy runner launches (bar_policy).
  • pianist_ros2 ships piano-task-specific launches: scene composition (pianist_bringup), the piano policy runner, and the USB-MIDI driver (both pianist_policy).

bar_description_lite/launch/view_lite.launch.py

URDF inspector — no controller_manager, no physics.

ArgDefaultEffect
rviz_configbundled view_lite.rvizOverride with your own RViz layout.

Implicit: forces use_fake_hardware:=true on the xacro so the <ros2_control> block is harmless when robot_state_publisher parses the URDF.

bar_bringup_lite/launch/real.launch.py

Real-hardware Lite bringup. Loads two bar_robstride/RobstrideSystem instances, one per physical SocketCAN bus (LiteLeftArm claims CAN ids 11..17 on the left bus, LiteRightArm claims 21..27 on the right bus).

ArgDefaultEffect
modearmsarms = 14 joints (default). arms_neck = 17 joints (requires neck silicon).
hardware_config<bar_bringup_lite share>/config/lite_hardware.yamlPer-machine bus + joint config. Maps the two <ros2_control> blocks to specific SocketCAN ifnames and joint IDs. Override to retarget a robot whose CAN ifnames differ.
calibration_file<bar_bringup_lite share>/config/calibration.yamlAbsolute path to the per-physical-robot zero-offset YAML. Pass '' for identity calibration (only the URDF direction sign flip applies, no offset). See Hardware specs → Bus-bring-up checklist for how to regenerate.
enable_mode_managertruefalse skips spawning the FSM orchestrator. Used by calibrate.launch.py and for raw-debug bringups where the operator drives controllers directly via ros2 control switch_controllers.
enable_gamepadtruetrue spawns joy_node so mode_manager can read /joy. The launch hard-fails on missing joy_dev. Pass false on a keyboardless lab box to drive the FSM via the /bar/mode/* std_srvs/Trigger services instead.
joy_dev/dev/input/js0Path passed verbatim to joy_node's dev parameter. Override when the onboard computer enumerates the gamepad as something other than js0 (multiple gamepads plugged in, udev rename). The pre-launch check fails fast when the specific path is missing and lists any other /dev/input/js* devices it can see, so the error message tells you which override to pass. Ignored when enable_gamepad:=false.

The active-policy target is picked by the START button, not a launch arg: R1+A activates remote_policy_controller (out-of-process policy, the real path today), R1+B activates rl_policy_controller (in-process RL — stub-only, see Controllers).

Visualisers are not in this launch. real.launch.py is the onboard-computer entrypoint of the tethered deployment split — it publishes /robot_description and /lite/joint_states over DDS but spawns no viewers. Run ros2 launch bar_bringup_lite viz.launch.py on the operator workstation (see the viz.launch.py section below).

Implicit on the xacro: use_fake_hardware:=false use_sim:=false.

bar_bringup_lite/launch/viz.launch.py

Host-side live visualiser. Runs on the operator workstation of the tethered deployment split (not on the onboard computer). Subscribes to the /robot_description (latched) and joint-state topic that real.launch.py is publishing on the onboard side and renders the live pose locally — purely a DDS consumer, no hardware coupling.

ArgDefaultEffect
viewerviserviser (browser at http://localhost:8080, works headless, screen-records cleanly) or rerun (native window, better for time-cursor / multi-stream UX on a workstation with a display). Mirrors mjlab's --viewer flag. choices= rejects other values at parse time.
joint_state_topic/lite/joint_statesTopic the viewer subscribes to. Override for a multi-robot deployment or a non-Lite robot.

Only one viewer spawns per launch — pick at invocation. Run the launch twice in two terminals if you need both viewers simultaneously (same pattern as running two mjlab play processes upstream).

bar_bringup_lite/launch/calibrate.launch.py

Bundles real.launch.py with three overrides (calibration_file:='' enable_mode_manager:='false' enable_gamepad:='false') and adds the calibrate_robot observer node. The plugin runs with identity calibration so /lite/joint_states carries direction × raw_motor_pos, which is the frame the homing-offset formula expects.

ArgDefaultEffect
hardware_config<bundled lite_hardware.yaml>Forwarded to real.launch.py.
output$PWD/calibration.yamlPath the calibration observer writes on Ctrl+C. After verifying, mv it over bar_bringup_lite/config/calibration.yaml to make it the default for the next real.launch.py.
sweep_threshold0.5Minimum joint sweep (rad) below which the prior homing_offset is preserved instead of recomputed. Lets you re-calibrate one or two joints at a time without losing the others.

The observer reads per-joint static config (direction, lower_limit, upper_limit, can_id) from /robot_description — there's no parallel YAML config for it to drift against. The YAML schema keeps the same per-joint keys as T-K-233/Lite-Lowlevel-Python's JSON output, so values move between the two stacks unchanged.

bar_bringup_lite/launch/mujoco.launch.py

MuJoCo Lite bringup. Loads mujoco_ros2_control/MujocoSystem inside the mujoco_sim process (which hosts the controller_manager as a physics plugin).

ArgDefaultEffect
modearmsSame as the real bringup. arms (14 joints) or arms_neck (17 joints).
hardware_config<bundled lite_hardware.yaml>Same as the real bringup; the bus mapping is unused in MuJoCo but the joint list is read.
sceneliteMJCF scene basename under bar_description_lite/mjcf/. Default lite (robot only). Task packages from sibling repos (e.g. pianist_ros2's pianist_bringup) compose their own runtime scene XML and override this arg with their composed-file basename.
enable_gamepadtrueSame hard-fail-on-missing-/dev/input/js* behaviour as the real bringup.

Implicit:

  • The xacro is invoked with use_sim:=true. use_sim wins over use_fake_hardware in the xacro's <plugin> selector — see the decision tree in Packages.
  • Every node runs with use_sim_time:=true. Time advances at MuJoCo's pace via /clock.
  • bar_bringup_lite/config/sim_overrides.yaml is layered on top of bar_controllers/config/bar_lite_controllers.yaml so the real-hardware launch stays sim-time-free.

bar_bringup_prime/launch/real.launch.py

Stub real-hardware Prime bringup. Designed to load both ethercat_driver/EthercatDriver (eRob arms) and bar_sito/SitoSystem (auxiliary) — two concurrent <ros2_control> blocks in the URDF.

The Prime URDF / MJCF is not yet imported from CAD — bar_bringup_prime is a stub today and this launch will not wire controllers until that import lands.

bar_bringup_prime/launch/mujoco.launch.py

Stub mirror of bar_bringup_lite/mujoco.launch.py for Prime, pending the Prime MJCF import.

bar_policy/launch/lite_policy.launch.py (generic)

Generic launcher for the tracking-family ONNX policies. The task:= arg picks which task within the family runs; all of them share the same bar_policy.remote_policy_runner executable (the ONNX metadata's task_type + observation_names distinguish them at load time).

ArgDefaultEffect
tasktrackingOne of tracking, reach, residual.
checkpoint_file(empty)Absolute path to a local ONNX checkpoint. Mutually exclusive with wandb_run_path.
wandb_run_path(empty)W&B run path (entity/project/run-id); the runner downloads + caches the ONNX.
wandb_checkpoint_name(empty)Specific checkpoint filename inside the run (model_2000.onnx etc.).
motion_file(empty)Local LeRobot dataset directory; overrides the ONNX dataset_repo_id.
registry_name(empty)HuggingFace LeRobot repo id override.
episode_index-1LeRobot dataset episode index (-1 = use whatever the ONNX metadata stored).

Sibling tracking-task families (piano, etc.) live in their own repos and register their own launch (see pianist_policy/piano_policy.launch.py below).

bar_policy/launch/lite_tracking.launch.py (legacy alias)

Thin wrapper around lite_policy.launch.py with task:=tracking pre-set. Kept for backwards compatibility with existing scripts and muscle memory; new launches should prefer the generic form.

pianist_policy/launch/piano_policy.launch.py

Same arg shape as lite_policy.launch.py but starts the pianist_policy.piano_policy_runner console script (which is a bar_policy.remote_policy_runner subclass adding the PianoSongTermProvider for song goal lookahead and progress, plus a re-publish of the song's goal frame each tick as /piano/target_keys so a bag recording is sufficient for offline F1).

ArgDefaultEffect
checkpoint_file(empty)Local ONNX path.
wandb_run_path(empty)W&B run path.
wandb_checkpoint_name(empty)Specific checkpoint filename.
motion_file(empty)Local LeRobot directory (overrides the registry pull).
registry_name(empty)HF Hub repo override for the reference dataset.
episode_index0Dataset episode index.

pianist_policy/launch/midi_keyboard_driver.launch.py

Starts the real-piano USB-MIDI driver standalone. Opens a MIDI input port and publishes pianist_msgs/PianoKeyState on /piano/key_state — the same topic + QoS as the sim-side piano_state_bridge, so the policy runner cannot tell them apart.

ArgDefaultEffect
port_name'' (auto-detect first available)MIDI input port name (or substring match). Use python -c 'import mido; print(mido.get_input_names())' to list available ports.
output_topic/piano/key_stateTopic to publish on.
publish_rate_hz50.0Publish rate for the latest pressed-state.

pianist_bringup/launch/mujoco.launch.py

MuJoCo bringup for the piano task. Composes the Lite robot and the piano MJCF into one scene file (_runtime_lite_piano.xml) inside bar_description_lite's MJCF share dir, then delegates to bar_bringup_lite/mujoco.launch.py with scene:=_runtime_lite_piano. Also spawns the piano_state_bridge sim-side bridge so /piano/key_state exists on the sim path.

ArgDefaultEffect
enable_gamepadtrueForwarded to bar_bringup_lite/mujoco.launch.py.
modearmsForwarded.
hardware_config<bar_bringup_lite share>/config/lite_hardware.yamlForwarded.

scene:= is not exposed — pianist_bringup controls that internally.

xacro args (bar_description_lite/urdf/lite.urdf.xacro)

The launch args ultimately feed these xacro args. Useful when driving xacro directly (e.g. in a sim2sim eval harness):

ArgDefaultEffect
use_fake_hardwaretrueSelect mock_components/GenericSystem — single combined <ros2_control> block. Only the xacro layer exposes this; no bundled launch uses it today.
use_simfalseWins over use_fake_hardware — select mujoco_ros2_control/MujocoSystem, also single combined block.
modearmsarms (14 joints) or arms_neck (17 joints). Selects which <ros2_control> block(s) the xacro emits.
hardware_config(empty)YAML the xacro reads to learn the per-machine bus + joint mapping. The launches set this; ad-hoc xacro calls usually leave it empty.
calibration_file""Passed verbatim as a <param name="calibration_file"> on both real-hardware blocks. Empty = identity calibration.

Common combinations

The launches are grouped by where they run. See Concepts → Architecture → Deployment topology for the rationale behind the split.

Single-machine dev path (sim, calibration, URDF inspection — no robot involved, no tether):

# Drag joints in RViz, no controllers.
ros2 launch bar_description_lite view_lite.launch.py

# MuJoCo physics, /clock from sim time.
ros2 launch bar_bringup_lite mujoco.launch.py

# Lite + piano in MuJoCo (pianist_bringup composes the scene).
ros2 launch pianist_bringup mujoco.launch.py

# Calibrate the zero pose (writes ./calibration.yaml on Ctrl+C).
ros2 launch bar_bringup_lite calibrate.launch.py

Robot onboard computer (CM + hardware + FSM + gamepad — boots the real control plane, no visualisers, no policy runner):

# Real Lite, gamepad on by default. Press R1+A at STANDBY to start the remote policy.
ros2 launch bar_bringup_lite real.launch.py

# Same, but on a keyboardless lab box (drive the FSM via /bar/mode/* services).
ros2 launch bar_bringup_lite real.launch.py enable_gamepad:=false

# Gamepad enumerated as js1 instead of js0 (multiple controllers plugged in).
ros2 launch bar_bringup_lite real.launch.py joy_dev:=/dev/input/js1

Operator workstation (host side of the tether — heavy ML deps, visualisers, optional MIDI input; talks to the robot strictly via DDS over a wired link):

# Live URDF + /lite/joint_states viewer (browser at :8080 by default).
ros2 launch bar_bringup_lite viz.launch.py # viser
ros2 launch bar_bringup_lite viz.launch.py viewer:=rerun # native rerun window

# Run a tracking policy (bar_policy) against a checkpoint on the HF Hub.
ros2 launch bar_policy lite_policy.launch.py \
task:=tracking \
wandb_run_path:=user/proj/run-id \
wandb_checkpoint_name:=model_2000.onnx

# Run a piano policy (pianist_policy) against a song.
ros2 launch pianist_policy piano_policy.launch.py \
wandb_run_path:=user/proj/run-id

# USB-MIDI keyboard driver (publishes /piano/key_state on this host —
# loopback to the piano policy runner; does not cross the tether).
ros2 launch pianist_policy midi_keyboard_driver.launch.py

Both machines must share ROS_DOMAIN_ID and (recommended) RMW_IMPLEMENTATION.