Skip to main content

Hardware specifications

This page is the source of truth for joint counts, actuator specs, and bus topology on Lite and Prime. The numbers here drive the joint limits in bar_description_* and the per-joint stiffness/damping defaults in bar_controllers/config/bar_*_controllers.yaml.

Lite humanoid

Bimanual upper body. 14 actuated DOFs by default (mode:=arms, 7 per arm). 17 actuated DOFs when the neck silicon is present (mode:=arms_neck, 7 + 7 + 3). The URDF kinematic chain always includes the neck links so robot_state_publisher exposes the same tf either way; the <ros2_control> neck block is added only in the 17-joint mode.

Lite kinematic tree

Joint table

Order matches the canonical index used by bar_lite_controllers.yaml, the C++ MITState struct, and the Python bar_policy.ObservationManager. Once a policy is trained against this order, it is frozen — see "Frozen schemas" in Architecture.

IdxJointCAN idBusModelDirectionLower (rad)Upper (rad)Effort (Nm)Current (A)K_pK_d
0left_shoulder_pitch11can0rs-02−1−3.1420.78517.02750.02.0
1left_shoulder_roll12can0rs-00−1−1.5711.92014.01650.02.0
2left_shoulder_yaw13can0rs-00+1−1.5711.57114.01650.02.0
3left_elbow_pitch14can0rs-00−1−2.3560.00014.01650.02.0
4left_wrist_yaw15can0rs-05+1−1.5711.5714.01450.02.0
5left_wrist_roll16can0rs-05−1−0.6980.6984.01450.02.0
6left_wrist_pitch17can0rs-05−1−0.7850.7854.01450.02.0
7right_shoulder_pitch21can1rs-02+1−3.1420.78517.02750.02.0
8right_shoulder_roll22can1rs-00−1−1.9201.57114.01650.02.0
9right_shoulder_yaw23can1rs-00+1−1.5711.57114.01650.02.0
10right_elbow_pitch24can1rs-00+1−2.3560.00014.01650.02.0
11right_wrist_yaw25can1rs-05+1−1.5711.5714.01450.02.0
12right_wrist_roll26can1rs-05+1−0.6980.6984.01450.02.0
13right_wrist_pitch27can1rs-05−1−0.7850.7854.01450.02.0

(In mode:=arms_neck, indices 14–16 = neck_yaw, neck_roll, neck_pitch, all rs-00-class with K_p ≈ 30, K_d ≈ 1.)

Where these numbers come from

Per-joint static config (CAN id, model, direction, position limits, torque cap, current cap) is the single source of truth in bar_description_lite/urdf/lite.ros2_control.xacro. Each value appears once, as a xacro arg on the lite_joint macro call:

<xacro:lite_joint name="left_shoulder_pitch" can_id="11" model="rs-02" direction="-1"
lower_limit="-3.141592653589793" upper_limit="0.7853981633974483"
torque_limit="17" current_limit="27"
use_fake_hardware="${use_fake_hardware}" use_sim="${use_sim}"/>

xacro expands those into <param> children on the <joint> element, which bar_robstride/RobstrideSystem::on_init reads (and, for torque_limit / current_limit, also writes to the actuator firmware at on_activate via the Robstride parameter IDs 0x700B and 0x7018 — same writes the upstream T-K-233/Lite-Lowlevel-Python's humanoid_control/control.py performs). Initial values were mirrored from that repo's configs/bimanual.yaml; if upstream retunes, edit them here in lockstep.

Default stiffness / damping reflects a conservative MIT-mode setting suitable for first activation; tune per deployment.

Retuning torque / current caps

The torque and current limits in the table above are firmware-enforced safety caps — the Robstride controller will refuse commands that exceed them, regardless of what a policy publishes. They're an upper bound, not a target. Lower them when bringing up a new policy on the bench; raise them once the motion envelope is verified.

Edit-rebuild loop:

  1. Open bar_description_lite/urdf/lite.ros2_control.xacro.

  2. Find the <xacro:lite_joint name="<joint>" …> call for the joint you want to retune (one per arm in lite_left_arm_joints / lite_right_arm_joints macros).

  3. Edit the torque_limit="…" (N·m, float) and / or current_limit="…" (A, float) attributes in place.

  4. Rebuild and re-launch:

    cd <workspace>/bar_ws
    pixi shell
    colcon build --symlink-install --packages-select bar_description_lite
    # If a bringup is already running, Ctrl+C it first — the firmware-side
    # caps are written on the `on_activate` transition, so an already-
    # activated plugin won't pick up the new value until the next bringup.
    ros2 launch bar_bringup_lite real.launch.py
  5. Confirm in the bringup log that the new value flowed through:

    [bar_robstride] Wrote torque_limit=15.0 to can_id=11 (left_shoulder_pitch)
    [bar_robstride] Wrote current_limit=20.0 to can_id=11 (left_shoulder_pitch)

No separate calibration step. Unlike homing_offset (per-physical-robot, lives in bar_bringup_lite/config/calibration.yaml), torque and current caps are per-robot-tuning — same value on every Lite physical instance, versioned alongside the URDF. If you want to A/B-test caps across deployments without editing source, set up two checked-out branches of bar_ros2 and switch between them rather than splitting the source of truth.

Setting to 0 disables the firmware write. The plugin treats torque_limit="0" / current_limit="0" as "skip the parameter write at on_activate" — useful when the actuator already has the right value written through some other tool (e.g. robstride_param_set on the bench) and you don't want this bringup to clobber it.

Firmware writes persist

Robstride actuators store parameter writes in non-volatile memory. If lite.ros2_control.xacro says torque_limit="17" and the firmware is later written with 12.0 by a different tool, the next bringup at this xacro state will overwrite 12.0 back to 17.0 at on_activate. The xacro is authoritative for what's on the bus, not just what's in this process.

Transports

Lite uses two SocketCAN buses (CAN-to-USB adapters), one per arm. Each bus is a separate <ros2_control> block in the URDF, each loading its own bar_robstride/RobstrideSystem instance. The default bus names come from bar_bringup_lite/config/lite_hardware.yaml, which the launch passes through to xacro as the hardware_config:= arg:

BlockDefault ifnameCAN ids
LiteLeftArmcan011..17
LiteRightArmcan121..27

Lite CAN topology

The controller_manager runs both plugin instances concurrently and exposes a single flat 14-joint list to controllers — they don't see the split.

Bus-bring-up checklist

# 1. Bring up both buses at 1 Mbps.
sudo ip link set can0 down 2>/dev/null
sudo ip link set can0 up type can bitrate 1000000
sudo ip link set can1 down 2>/dev/null
sudo ip link set can1 up type can bitrate 1000000

# 2. Read-only sanity scan — no Enable, no MIT.
# (the `bar` and `ros2` CLIs assume you've `cd bar_ws && pixi shell`'d.)
bar bus discover --iface can0 --scan-to 32
bar bus discover --iface can1 --scan-to 32
# Expect 7 + 7 = 14 actuators replying at ids 11..17 and 21..27.

# 3. Calibrate the zero pose (once per physical robot).
ros2 launch bar_bringup_lite calibrate.launch.py
# Hand-sweep every joint to both extremes. Ctrl+C to write calibration.yaml.

# 4. Real-hardware bringup.
ros2 launch bar_bringup_lite real.launch.py

If bar bus discover reports ENOBUFS / TX-drop warnings, the actuator power is off (no ACKs → frames pile up in the kernel qdisc). Power the motors first.

IMU

A single serial / USB IMU publishes sensor_msgs/Imu on /imu/data. It is not routed through ros2_control as a SensorInterface — a blocking serial read inside the controller_manager read() cycle would block the RT loop. Consumers (RLPolicyController, bar_policy) cache the latest sample via realtime_tools::RealtimeBuffer.

Prime humanoid

Bimanual with EtherCAT-driven eRob actuators in the arms and SocketCAN-driven Sito actuators for auxiliary joints, running concurrently in the same controller_manager.

Prime URDF is not yet imported

The Prime mechanical CAD has not been finalized at the time of writing. bar_description_prime is a placeholder package; bar_lite_controllers.yaml binds 17 real joints, but bar_prime_controllers.yaml is still ["__placeholder__"]. Joint specs below are projections, not commitments.

Projected joint topology

Prime is unique in that two <ros2_control> blocks coexist in its URDF — one binds ethercat_driver/EthercatDriver, the other binds bar_sito/SitoSystem. The controller_manager runs both concurrently; controllers see a single flat joint list regardless of which bus carries them.

MIT-mode command convention

Every actuator on both robots (and every sim system) implements a hybrid position-velocity-torque command that is the central abstraction of the project:

MIT-mode hybrid command

Every controller in bar_controllers claims all five command interfaces, even when it only writes some of them (writing zero to the rest is the safe default — for example ZeroTorqueController writes 0 to everything; DampingController writes K=0, D=damping_value, q_cmd=captured_q).

Why this convention pays off

The exact same formula is implemented in the Robstride motor firmware, in mujoco_ros2_control::MujocoSystem (verified in mujoco_system.cpp), and in any controller we write. As a result a policy that ran on Lite in simulation runs unchanged against the real Lite — no gain remapping, no quirk shims.

The names stiffness and damping are taken verbatim from mujoco_ros2_control::MujocoSystem (HW_IF_STIFFNESS = "stiffness", HW_IF_DAMPING = "damping") so the same controller binds identically against silicon and sim with no URDF interface-tag rewrites.

Reference & next