Layer 1 — Hardware Abstraction (HAL)
Part of the OpenRAL public-symbol inventory. Hand-curated;
(LNN)markers are refreshed bytools/refresh_methods_linenos.py.
python/hal/src/openral_hal/protocol.py
HAL Protocol — the normative interface every HAL adapter must satisfy.
class HAL(Protocol)— Structural protocol every HAL adapter must satisfy. (L26)- attr
description: RobotDescription connect() -> None— Open connection to robot/sim. (L43)disconnect() -> None— Close connection (idempotent). (L53)read_state() -> JointState— Latest joint state snapshot (hot path). (L61)send_action(action: Action) -> None— Forward action chunk to controller (hot path). (L75)estop() -> None— Trigger emergency stop, always raisesROSEStopRequested. (L91)
python/hal/src/openral_hal/_mujoco_arm.py
Internal MuJoCo-backed HAL implementation shared by UR / Franka / SO-100 / G1 / H1 / Rizon-4 / OpenArm / ALOHA adapters. Reads its wiring from RobotDescription.sim (ADR-0023).
class _MujocoArmInitKwargs(TypedDict)— Typed shape of the kwargs accepted byMujocoArmHAL.__init__. (L59) LetsMujocoArmHAL._sim_kwargs_forreturn a value that unpacks cleanly into the constructor undermypy --strictwithout the# type: ignore[arg-type]hatch every thin subclass used to need. Fields:mjcf_path, joint_qpos_addr, joint_qvel_addr, actuator_index, grippers, keyframe_index, seed_ctrl_from_qpos, settle_steps, gravity_enabled, staleness_limit_s._resolve_mjcf_path(desc: RobotDescription) -> str[private] — Resolvedesc.assets.mjcf(ADR-0058) to an absolute MJCF path viaopenral_core.assets.resolve_asset; raisesROSConfigErrorwhen the ref is unset or unresolvable. Replaced the former publicresolve_mjcf_uri/SimDescription.mjcf_uri(ADR-0058). (L79)build_hal(description, *, mode: Literal["sim","real"], transport=None, sim_env_yaml=None) -> HAL— Single seam for constructing a robot's simulation or real-hardware HAL from its manifest (resolver.py, L50).mode="sim"+sim_env_yamlset → callsbuild_sim_env_from_yamland returns aSimAttachedHALwrapping the scene'sSimRollout(ADR-0034); bypasses the bare-twin /hal.simclass entirely.mode="sim"withoutsim_env_yamlbuildsdescription.hal.simor derivesMujocoArmHAL.from_descriptionwhen it is null + asim:block exists.mode="real"importsdescription.hal.realand threadstransportkwargs (real HALs takeport/robot_ip/fci_ipand embed their own description). Both modes mergedescription.hal.parameters.defaults(ADR-0029) underneath the explicittransportso the manifest carries a robot's construction kwargs; unaccepted keys are dropped.sim_env_yaml+mode="real"→ROSConfigError. Missing HAL for the mode →ROSCapabilityMismatch; malformed/unresolvable entry →ROSConfigError. Routed bydeploy sim(sim) anddeploy run(real). (ADR-0031, ADR-0034)_import_object(path: str) -> object[private] — Resolve a"module.path:Attribute"import string; raisesROSConfigErroron malformed/unimportable/missing. Reuse watch: the canonical entrypoint-string importer for HAL classes — do not hand-rollimportlibin HAL callers.class MujocoArmHAL— Generic MuJoCo-backed HAL adapter for position-controlled arms (and, via the_per_step_updatehook, torque-controlled humanoids like the H1). (L112)read_images() -> dict[str, NDArray]— Render the manifest's RGBSensorSpecs off the live MJCF, keyed by sensorname(issue #191 Phase 3b). Same contractSimAttachedHAL.read_imagesexposes, soSimSensorBridgepublishes a composed-scene arm's cameras (openarm) through the shared path. Renders the MJCF camerasim_camera_name or name; a missing camera / render error is skipped with a one-shot warning (never raises). Themujoco.Rendereris lazily created on first call so its EGL context binds on the caller (executor) thread. Returns{}when disconnected / no RGB sensors / after a renderer failure.__init__(description, *, mjcf_path, joint_qpos_addr, actuator_index, joint_qvel_addr=None, grippers=(), keyframe_index=None, seed_ctrl_from_qpos=False, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)— Init only; MJCF is not loaded untilconnect().joint_qvel_addrdefaults tojoint_qpos_addr(correct for arms without a floating base) and is passed explicitly by humanoid HALs likeG1MujocoHAL/H1MujocoHALwhere the free joint shifts the qvel indices by 1.grippersis a sequence ofSimGripperDescriptionentries; single-arm robots ship one (or none), bimanual robots (Aloha, OpenArm) ship two. (L162)_per_step_update(targets) -> None— Hook invoked before everymj_stepinside the settle loop. Default no-op; subclasses driving torque-mode actuators (H1MujocoHAL) override to recompute the actuator torque each step from the currentqpos/qvel.connect() -> None— Load MJCF, prepareMjDatabuffer.disconnect() -> None— Release the MuJoCo model (idempotent).read_state() -> JointState— Joint state in description-joint order. Reads live in-processMjData(always current), so it never latchesROSPerceptionStale: a gap >staleness_limit_ssince the last service means the single-threaded executor was starved (e.g. a slow camera render), not bad data — it emits a one-shothal.read_state.starvedWARNING and returns the live state (re-armed on the next healthy read). The prior behaviour raised before refreshing the clock, so one transient stall bricked the HAL permanently (the deploy-sim "Joint state is X s old" loop). Async live-feedback staleness is policed by the subscription HALs (ros_control/aloha), not here.send_action(action: Action) -> None— Forward last waypoint to MuJoCo and step. Stamps_last_action_nsso the idle stepper yields to a recent command.idle_step() -> bool— Sim-only HOLD stepper that gives a bareMujocoArmHALthe ADR-0034 (idle cameras stay live) + ADR-0049 (joint_state published off the executor viaProprioSnapshot+ dedicated thread) treatment the lifecycle node gates on a callableidle_step. Leavesctrluntouched (it already holds the last commanded / seeded pose) and advances onemj_stepso physics + the staleness clock refresh without moving the arm. ReturnsFalse(no-op) when not connected — i.e. afterestop()disconnects — so it can never autonomously drive an e-stopped robot;Trueotherwise. Defined on the sim-onlyMujocoArmHALhierarchy only (no real HAL inherits it), mirroring the same method-only real-hardware guard asSimAttachedHAL.idle_step.- (property)
last_action_ns -> int—time.monotonic_ns()of the lastsend_action(0if never actuated → idle-stepping starts immediately). TheSimSensorBridgereads it (should_idle_step) to yield the idle stepper to a recently-commanded skill. MirrorsSimAttachedHAL.last_action_ns. reset_to_pose(pose: list[float]) -> None— Snapqposto a manifeststarting_poseand re-seedctrl(instantaneous teleport; best-effort). The ADR-0053 collision-aware alternative is not a HAL method — the runner dispatches therskill-moveit-jointsrSkill to plan a collision-free MoveGroup motion tostarting_pose(see05-inference-runner/08-cli). (L505)estop() -> None— Zeroctrland raiseROSEStopRequested.- (classmethod)
from_description(description, *, settle_steps=None, gravity_enabled=True, staleness_limit_s=0.5, mjcf_path_override=None) -> MujocoArmHAL— Manifest-driven constructor. Readsdescription.simand builds the HAL with the right MJCF path, qpos/qvel/actuator maps and gripper config. Removes the need for per-robot Python subclasses (ADR-0023). (L808) - (staticmethod)
_sim_kwargs_for(description, *, settle_steps=None, gravity_enabled=True, staleness_limit_s=0.5, mjcf_path_override=None) -> _MujocoArmInitKwargs— Translatedescription.siminto the__init__kwarg dict. Default 1:1 joint→qpos/actuator mapping is derived fromdescription.joints, offset by 7 (qpos) / 6 (qvel) whensim.floating_base=True. Used by bothfrom_description,_init_from_description, and any caller that wants to post-process the kwargs. (L732) - (instance method)
_init_from_description(description, *, mjcf_path=None, settle_steps=None, gravity_enabled=True, staleness_limit_s=0.5) -> None— Seam every thin per-robot subclass (UR5e/UR10e, Franka, ALOHA, OpenArm, Rizon4, G1, H1, SO-100) uses to drop the boilerplatesuper().__init__(DESC, **MujocoArmHAL._sim_kwargs_for(DESC, …))dance. Subclasses keep their typed__init__(*, mjcf_path, settle_steps, gravity_enabled, staleness_limit_s)signature (so IDEs still surface the four user-tunable knobs) and forward straight to here. (L864) - private:
_require_connected,_validate_action,_last_arm_targets,_apply_arm_targets,_apply_gripper_target,_read_gripper_normalised,_effective_actuator_index_for
python/hal/src/openral_hal/_real_description.py
Internal helper to derive a real-hardware RobotDescription from a sim baseline.
make_real_description(base, *, sdk_kind) -> RobotDescription—model_copy(update={"sdk_kind": sdk_kind}); thehalentrypoints (hal.sim/hal.real) are inherited from base (ADR-0031). (L48)
python/hal/src/openral_hal/franka_panda.py
HAL adapter for the Franka Emika Panda 7-DoF arm (sim, MuJoCo).
class FrankaPandaHAL(MujocoArmHAL)— Franka Panda HAL (MuJoCo-backed). Thin manifest-driven wrapper aroundMujocoArmHAL;__init__forwards toself._init_from_description(FRANKA_PANDA_DESCRIPTION, …)(ADR-0023). (L266)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)(L295)_panda_joint_specs() -> list[JointSpec](L122)- const
FRANKA_PANDA_DESCRIPTION = RobotDescription(...)(L176) — sim baseline;sdk_kind="open",hal.sim="openral_hal.franka_panda:FrankaPandaHAL"+hal.real="openral_hal.franka_panda_real:FrankaPandaRealHAL"(ADR-0031). All MuJoCo wiring (MJCF URI, joint→qpos/actuator maps, gripper config) lives inFRANKA_PANDA_DESCRIPTION.sim. The real-HW companionFRANKA_PANDA_REAL_DESCRIPTIONlives infranka_panda_real.py.
python/hal/src/openral_hal/franka_panda_real.py
Real-hardware HAL adapter for the Franka Emika Panda over the FCI (issue #56).
class FrankaPandaRealHAL— Production adapter for a physical Panda overfranka_ros2/ FCI. WrapsRosControlHALvia composition. (L90)__init__(*, fci_ip='172.16.0.2', controller_name='franka_arm_controller', joint_state_topic='/joint_states', command_topic=None, error_recovery_topic='/error_recovery/goal', publish_fn=None, state_fn=None, staleness_limit_s=0.2)(L144)description -> RobotDescription[@property] — ReturnsFRANKA_PANDA_REAL_DESCRIPTION. (L180)controller_name -> str[@property] (L185)fci_ip -> str[@property] (L190)connect() -> None(L196)disconnect() -> None(L214)read_state() -> JointState(L220)send_action(action) -> None(L230)estop() -> None— Publishes to/error_recovery/goalthen raisesROSEStopRequested. (L246)- const
FRANKA_PANDA_REAL_DESCRIPTION = make_real_description(FRANKA_PANDA_DESCRIPTION, sdk_kind="closed_with_api")(L84) — inherits the sharedhal; whatrobots/franka_panda/robot.yamlmirrors.
python/hal/src/openral_hal/sawyer_real.py
Real-hardware HAL adapter for the Rethink Sawyer 7-DoF arm (issue #57).
class SawyerRealHAL— Production adapter for a physical Sawyer overintera_sdk/sawyer_robot. (L220)__init__(*, hostname='sawyer.local', controller_name='sawyer_arm_controller', joint_state_topic='/robot/joint_states', command_topic=None, estop_topic='/robot/set_super_stop', publish_fn=None, state_fn=None, staleness_limit_s=0.2)(L267)description -> RobotDescription[@property] — MirrorsSAWYER_DESCRIPTION. (L303)hostname -> str[@property] (L308)controller_name -> str[@property] (L313)connect() -> None(L317)disconnect() -> None(L331)read_state() -> JointState(L335)send_action(action) -> None(L345)estop() -> None(L355)_sawyer_joint_specs() -> list[JointSpec](L112)- const
SAWYER_DESCRIPTION = RobotDescription(...)(L155) — sim baseline;sdk_kind="open",hal.sim=None(no MuJoCo HAL adapter today) +hal.real="openral_hal.sawyer_real:SawyerRealHAL". - const
SAWYER_REAL_DESCRIPTION = make_real_description(SAWYER_DESCRIPTION, sdk_kind="closed_with_api")(L195) — inherits the sharedhal; whatrobots/sawyer/robot.yamlmirrors.
python/hal/src/openral_hal/panda_mobile.py
ADR-0025 — in-process digital-twin HAL for the panda_mobile embodiment (Franka 7-DoF arm on a holonomic 3-DoF base). Built by build_hal for the manifest-driven ManifestHALLifecycleNode (issue #191 Phase 3) and by tests; ROS node entrypoint in packages/openral_hal_panda_mobile/.
- const
PANDA_MOBILE_BASE_JOINT_NAMES: list[str]— Base joints[base_x, base_y, base_yaw], derived fromPANDA_MOBILE_DESCRIPTION.base_joints(not hardcoded). (L100) - const
PANDA_MOBILE_JOINT_NAMES: list[str]— Full 11-DoF order: base (3) + arm (7, role-derived) + gripper (1, role-derived) — all from the description. (L116) - const
PANDA_MOBILE_DESCRIPTION: RobotDescription— Canonical RobotDescription, loaded fromrobots/panda_mobile/robot.yamlat module import. Single source of truth for joint metadata +sim_joint_nameoverrides; the arm/base/gripper name constants above derive from it viaJointSpec.role. (L93) class PandaMobileHAL— In-process digital-twin HAL. RoutesBODY_TWIST→ planar Euler integration of (vx, vy, wz); routesJOINT_POSITION→ 7-vec arm targets or 11-vec base+arm+gripper targets. (L132)- (removed: the
base_sim_joint_namesre-export wrapper — callers now importopenral_core.extract_base_sim_joint_namesdirectly.)
python/hal/src/openral_hal/depth_cloud.py
ADR-0030 — reusable, robot-agnostic depth-camera → sensor_msgs/PointCloud2 plumbing for deploy-sim HAL nodes (octomap_server source → kernel world-collision check). Pure SensorSpec adapters + the ROS msg builder; the ray-cast synth lives in openral_sim.backends.depth_camera.
- is_depth_sensor(spec) -> bool — True when spec.modality in ("depth", "point_cloud") and it carries pinhole intrinsics (required to back-project). (L35)
- mjcf_camera_name(spec) -> str — Resolves the backing MJCF <camera> name: spec.metadata["mjcf_camera"] if set (the sim camera name can differ from the ROS sensor name), else spec.name. (L44)
- robot_self_body_ids(model, sim_joint_names) -> frozenset[int] — Every MJCF body whose name shares a first-_-token prefix with one of the robot's sim_joint_names (e.g. mobilebase0 / robot0 / gripper0). Passed as synthesize_depth_pointcloud(exclude_body_ids=…) so the depth cloud is self-filtered (the robot is not voxelised into its own world map). (L99)
- depth_synth_kwargs(spec, *, max_range_default, render_size=None) -> dict — Maps a depth SensorSpec to synthesize_depth_pointcloud kwargs (width/height/fx/fy/cx/cy + min_range_m/max_range_m from range_min_m/range_max_m, falling back to max_range_default). ADR-0035: when render_size=(width, height) is given (the scene's observation_width/height), the intrinsics are first rescaled via openral_core.scale_intrinsics_to so the ray-cast grid matches the render resolution. (L57)
- resolve_base_body_name(model, *, description=None) -> str | None — Resolve the MJCF body backing the robot's base_frame: when a RobotDescription is given, the first base joint's prefix + _base (mobilebase0_base); then the bare candidates mobilebase0_base / base / robot0_base / base_link — mobilebase0_base tried before robot0_base because in composed robosuite/RoboCasa scenes robot0_base is a placeholder mount at a fixed offset; None if none exist. Backs both the depth/TF base resolution (SimSensorBridge._resolve_depth_base_body) and the viewer free-camera fallback. (L122)
- preferred_viewer_camera_id(model, *, prefer=("agentview","top","frontview","front")) -> int — Pick the named MJCF camera whose vantage the viewer should open from: the first camera whose name contains a prefer substring (a 3rd-person workspace view — robot0_agentview_left, top, agentview), else the first declared camera (e.g. a wrist/eye-in-hand cam), else -1 when the model has no cameras. Scene cameras are authored to frame the action, sidestepping the free orbit's occlusion in cluttered scenes (a base-centred orbit in a RoboCasa kitchen stares at a wall). Consumed by initial_viewer_camera. (L168)
- initial_viewer_camera(*, model, data, description=None) -> tuple[tuple[float,float,float], float, float, float] — Opening free-camera pose (lookat, distance, azimuth_deg, elevation_deg) for the viewer. The viewer always uses mjCAMERA_FREE so the user keeps full mouse control (drag-orbit, scroll-zoom) — this only sets the initial view; a mjCAMERA_FIXED lock would freeze those controls. When preferred_viewer_camera_id finds an authored camera, the eye is placed at that camera's data.cam_xpos with the orbit pivot on the robot base (resolve_base_body_name, else model.stat.center), so the opening view matches the authored vantage yet orbits around the robot; else delegates to base_aligned_free_camera. Reproduces the eye exactly via MuJoCo's eye = lookat − distance·f, f = (cos el cos az, cos el sin az, sin el). (L335)
- apply_robosuite_visual_geomgroups(opt, model) -> bool — For a robosuite/RoboCasa model, set opt.geomgroup to hide collision shells (group 0 — RoboCasa's red kitchen / green robot capsules) and show the textured visual geoms (group 1), so mujoco.viewer renders textures instead of a red collision box. Gated on a robosuite signature (a robot0_/gripper0_/mobilebase0_ body or an agentview/frontview camera) — not geom counts, since dm_control/gym scenes (gym-aloha) put visuals in group 0; returns True when it acted, False (no-op) otherwise. Used by the eval sim run --view viewer. (L211)
- base_aligned_free_camera(*, model, data, base_body_name=None, azimuth_offset_deg=135.0, elevation_deg=-25.0, distance_scale=2.0, max_distance_m=3.5) -> tuple[tuple[float,float,float], float, float, float] — Fallback free-camera framing (lookat_xyz, distance, azimuth_deg, elevation_deg) for camera-less models (single-robot twins): centres on the robot base and offsets the azimuth by the base frame's world yaw so the view aligns to the base's own axes (MuJoCo's world frame is immutable, so the viewer cannot be re-rooted onto base_link). distance is distance_scale × model.stat.extent capped at max_distance_m (a composed scene's whole-model extent would otherwise push the camera tens of metres out). Falls back to model.stat.center with no yaw when base_body_name is None/absent. Shared with the openral sim run --view eval path. (L246)
- camera_optical_tf_to_base(*, model, data, camera_name, base_body_name) -> tuple[tuple[float,float,float], tuple[float,float,float,float]] — Live (translation_xyz, quat_xyzw) of the camera optical frame (REP-103) expressed in the base body, from data.cam_xpos/cam_xmat vs the base body pose, so a node broadcasts base_frame → <camera>_optical_frame. Raises ROSConfigError if camera/body absent. (L388)
- pointcloud2_from_points_xyz(points, *, frame_id, stamp=None) -> PointCloud2 — Packs an (N, 3) float32 array into an unordered (height=1) XYZ-float32 sensor_msgs/PointCloud2 — the layout octomap_server's cloud_in expects (sensor_msgs imported lazily). (L440)
python/hal/src/openral_hal/aloha.py
HAL adapter for the Trossen ALOHA bimanual setup (issue #58) + the MuJoCo digital twin.
class AlohaHAL(HALBase)— Real-hardware adapter for the 14-DoF ALOHA over the Interbotix XS SDK. (L336)__init__(*, left_arm_controller='left_arm/arm_controller', right_arm_controller='right_arm/arm_controller', left_gripper_controller='left_arm/gripper_controller', right_gripper_controller='right_arm/gripper_controller', joint_state_topic='/joint_states', estop_topic='/aloha/estop', publish_fn=None, state_fn=None, staleness_limit_s=0.2)(L384)connect() -> None(L415)disconnect() -> None(L432)read_state() -> JointState(L439)send_action(action) -> None— Splits the 14-D action 4-ways across per-arm + per-gripper controllers. (L471)estop() -> None(L535)- private:
_require_connected class AlohaMujocoHAL(MujocoArmHAL)— MuJoCo digital twin for the 14-DoF bimanual ALOHA; thin manifest-driven wrapper aroundMujocoArmHAL(ADR-0023 bimanual amendment). All wiring lives inALOHA_DESCRIPTION.sim:gym_aloha:bimanual_viperx_transfer_cubeURI, explicitjoint_qpos_addr/actuator_index(left arm 0-5, left gripper 6, right arm 8-13, right gripper 14 — skipping the negative-finger slots), twoPASSTHROUGHgrippers withmirror_actuator_index(positive finger + negative finger),keyframe_index: 0(seeds the fingers insidectrlrange=[0.021, 0.057]). (L572)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)— Forwards toself._init_from_description(ALOHA_DESCRIPTION, …). (L607)_aloha_joint_specs() -> list[JointSpec](L151)_default_publish(topic, msg) -> None(L560)- const
ALOHA_DESCRIPTION = RobotDescription(...)(L195) — sim baseline;sdk_kind="open",hal.sim="openral_hal.aloha:AlohaMujocoHAL"+hal.real="openral_hal.aloha:AlohaHAL". - const
ALOHA_REAL_DESCRIPTION = make_real_description(ALOHA_DESCRIPTION, sdk_kind="closed_with_api")(L307) — inherits the sharedhal; whatrobots/aloha_bimanual/robot.yamlmirrors.
python/hal/src/openral_hal/ur.py
HAL adapters for the Universal Robots UR5e and UR10e arms (sim, MuJoCo).
class UR5eHAL(MujocoArmHAL)— UR5e HAL (MuJoCo-backed). Thin manifest-driven wrapper;__init__forwards toself._init_from_description(UR5e_DESCRIPTION, …)(ADR-0023). (L302)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)(L326)class UR10eHAL(MujocoArmHAL)— UR10e HAL (MuJoCo-backed). Same shape asUR5eHAL(ADR-0023). (L344)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)(L356)ur5e_with_sensors(catalog_ids=None) -> RobotDescription(L246)ur10e_with_sensors(catalog_ids=None) -> RobotDescription(L272)_ur_joint_specs(velocity_limits, effort_limits) -> list[JointSpec](L119)- const
UR5e_DESCRIPTION = RobotDescription(...)(L157) — sim manifest; all MuJoCo wiring lives inUR5e_DESCRIPTION.sim. - const
UR10e_DESCRIPTION = RobotDescription(...)(L201) — sim manifest; all MuJoCo wiring lives inUR10e_DESCRIPTION.sim.
python/hal/src/openral_hal/ur_real.py
Real-hardware HAL adapters for UR5e / UR10e via ros2_control + ur_robot_driver (URCap / RTDE).
class UR5eRealHAL(_URRealHAL)— Real UR5e viaur_robot_driver. (L147)class UR10eRealHAL(_URRealHAL)— Real UR10e viaur_robot_driver. (L199)class _URRealHAL(RosControlHAL)— Shared real-HW base (controller / topic defaults +deadman_topic). (L88)- const
UR5e_REAL_DESCRIPTION = make_real_description(UR5e_DESCRIPTION, sdk_kind="closed")(L77) — inherits the sharedhal; whatrobots/ur5e/robot.yamlmirrors. - const
UR10e_REAL_DESCRIPTION = make_real_description(UR10e_DESCRIPTION, sdk_kind="closed")(L82) — inherits the sharedhal; whatrobots/ur10e/robot.yamlmirrors.
python/hal/src/openral_hal/so100_follower.py
SO100FollowerHAL — wraps lerobot's SO-100 follower arm USB driver.
class SO100FollowerHAL— HAL adapter wrapping lerobot's SO-100 follower. (L246)__init__(port='/dev/ttyUSB0', *, calibrate_on_connect=False, max_relative_target=None, staleness_limit_s=0.5, robot=None)(L288)connect() -> None— Open USB serial connection. (L312)disconnect() -> None— Close USB, disable motor torque (idempotent). (L378)read_state() -> JointState— Joint state in radians. (L391)send_action(action: Action) -> None— Forward one step to the SO-100 motor bus. (L419)estop() -> None— Disconnect motors then raise. (L442)_require_connected(operation: str),_obs_to_positions(obs)[@staticmethod],_action_to_lerobot(action)_deg_to_rad(deg) -> float(L233)_rad_to_deg(rad) -> float(L238)- const
SO100_DESCRIPTION = RobotDescription(...)(L88)
python/hal/src/openral_hal/h1.py
MuJoCo digital twin for the Unitree H1 humanoid (Menagerie MJCF). Contract validator only — falls without an S0 cerebellum; gravity must be disabled in closed-loop tests (CLAUDE.md §6.2). Unlike the G1 / UR / Franka / SO-100 MJCFs, the H1 menagerie ships motor (torque) actuators, so this HAL runs a software PD position loop every physics step.
class H1MujocoHAL(MujocoArmHAL)— 19-DoF humanoid HAL drivingmujoco_menagerie/unitree_h1/h1.xml. Joint inventory: 5 leg + 5 leg + 1 torso + 4 arm + 4 arm (no wrists). Thin manifest-driven wrapper aroundMujocoArmHAL(ADR-0023);__init__forwards toself._init_from_description(H1_DESCRIPTION, …). Inheritsconnect/disconnect/read_state/estop; overrides_apply_arm_targetsto a no-op and_per_step_updateto computetau = kp*(target - q) - kv*dqclamped toctrlrangeso the public action contract stays "position targets in radians". Mirrors howunitree_sdk2wraps motor-level torque control in a position loop on real hardware. (L359)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)(L399)_per_step_update(targets) -> None— Recomputes PD torque everymj_step._apply_arm_targets(targets) -> None— No-op (PD loop runs per-step instead)._h1_group(joint_name) -> str— Return the kinematic group token (hip/knee/ankle/torso/shoulder/elbow) forjoint_name. (L209)_h1_parent_child(joint_name) -> tuple[str, str]— Return(parent_link, child_link)for an H1 joint. (L217)_h1_joint_specs() -> list[JointSpec]— Build the 19JointSpecs from the joint-name tuples + the per-joint limit tables. (L253)_h1_pd_gains() -> dict[str, tuple[float, float]]— Per-joint(kp, kv)for the software PD loop (kv = 0.05*kp; kp sized so a 1-rad error roughly saturates each actuator's ctrlrange). (L350)- const
H1_DESCRIPTION = RobotDescription(...)(L276) — sim baseline;sdk_kind="open",hal.sim="openral_hal.h1:H1MujocoHAL"+hal.real=None(sim-only until M2). All MuJoCo wiring (MJCF URI, floating-base joint offsets +7/+6, PD gains) lives inH1_DESCRIPTION.sim. Drift-guarded againstrobots/h1/robot.yamlbytests/unit/test_robot_manifests_match_hal_constants.py.
python/hal/src/openral_hal/flexiv_rizon4.py
MuJoCo digital twin for the Flexiv Rizon 4 — 7-DoF cobot with whole-body force sensitivity (0.1 N). Structurally identical to the UR / Franka sim HALs: position actuators, no gripper, no floating base, no PD-loop overrides — a clean MujocoArmHAL subclass.
class Rizon4MujocoHAL(MujocoArmHAL)— 7-DoF HAL drivingmujoco_menagerie/flexiv_rizon4/flexiv_rizon4.xmlviaMujocoArmHAL. Thin manifest-driven wrapper (ADR-0023);__init__forwards toself._init_from_description(RIZON4_DESCRIPTION, …). (L180)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)(L210)_rizon4_joint_specs() -> list[JointSpec]— Build the 7JointSpecs from the joint-name tuple + per-joint limit tables. (L111)- const
RIZON4_DESCRIPTION = RobotDescription(...)(L132) — sim baseline;sdk_kind="open",hal.sim="openral_hal.flexiv_rizon4:Rizon4MujocoHAL"+hal.real=None(sim-only). All MuJoCo wiring lives inRIZON4_DESCRIPTION.sim. Drift-guarded againstrobots/rizon4/robot.yamlbytests/unit/test_robot_manifests_match_hal_constants.py.
python/hal/src/openral_hal/openarm.py
MuJoCo digital twin for the Enactic OpenArm v2 bimanual humanoid arm. Fresh HALBase subclass — v2's native <position> actuators with per-class PD baked into the MJCF mean the HAL just writes target → ctrl and steps, no software PD loop needed.
class OpenArmMujocoHAL(MujocoArmHAL)— 16-DoF (7 arm + 1 gripper per side) bimanual HAL drivingenactic/openarm_mujoco/v2/openarm_v20_bimanual.xml; thin manifest-driven wrapper aroundMujocoArmHAL(ADR-0023 bimanual amendment). All wiring lives inOPENARM_DESCRIPTION.sim:openarm_v2:bimanualURI (fetched lazily viaensure_openarm_v2_mjcf), explicitjoint_qpos_addrthat skips the passive follower-finger qpos slots (8, 17), twoPASSTHROUGHgrippers (left jaw[0, 0.7854], right jaw[-0.7854, 0]),seed_ctrl_from_qpos: trueso the v2<position>actuators hold the initial pose on the firstmj_step. (L419)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)— Forwards toself._init_from_description(OPENARM_DESCRIPTION, …). (L454)_openarm_arm_joint_specs(names, position_limits, side) -> list[JointSpec],_openarm_gripper_joint_spec(name, side, position_limits) -> JointSpec,_openarm_joint_specs() -> list[JointSpec](L167, L190, L206)- const
OPENARM_DESCRIPTION = RobotDescription(...)(L237) — sim baseline (name="openarm_v2", all 16 joints revolute matching v2's hinge gripper).sdk_kind="open",hal.sim="openral_hal.openarm:OpenArmMujocoHAL"+hal.real=None(sim-only). Drift-guarded againstrobots/openarm/robot.yaml.
python/hal/src/openral_hal/_openarm_v2_assets.py
Vendor the upstream enactic/openarm_mujoco v2 MJCF until robot_descriptions bumps its pin past PR #19.
ensure_openarm_v2_mjcf() -> str— Idempotently clonesenactic/openarm_mujocoat a pinned v2 SHA into$OPENRAL_CACHE_DIR/openarm_v2/<sha>/, returns the bimanual MJCF path. RaisesROSConfigErrorwhengitis missing or the clone fails. Mirrors the pattern used bypython/sim/src/openral_sim/backends/so100_robosuite/_assets.py. (L64)- module const
_OPENARM_V2_PINNED_SHA: str(L47) — bump to track upstream v2 updates.
python/hal/src/openral_hal/g1.py
MuJoCo digital twin for the Unitree G1 humanoid (Menagerie MJCF). Contract validator only — falls without an S0 cerebellum, gravity must be disabled in closed-loop tests (CLAUDE.md §6.2).
class G1MujocoHAL(MujocoArmHAL)— 29-DoF humanoid HAL drivingmujoco_menagerie/unitree_g1/g1.xmlviaMujocoArmHALwith an explicitjoint_qvel_addrmapping (the free joint occupies 7 qpos slots but only 6 qvel slots). Floating-base joint is implicit world state, not indescription.joints. Thin manifest-driven wrapper (ADR-0023);__init__forwards toself._init_from_description(G1_DESCRIPTION, …). (L347)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)_g1_group(joint_name) -> str— Return the kinematic group token (hip/knee/ankle/waist/shoulder/elbow/wrist) forjoint_name. (L205)_g1_parent_child(joint_name) -> tuple[str, str]— Return(parent_link, child_link)for a G1 joint, following the menagerie URDF convention. (L213)_g1_joint_specs() -> list[JointSpec]— Build the 29JointSpecs from the joint-name tuples and the per-joint limit tables. (L263)- const
G1_DESCRIPTION = RobotDescription(...)(L291) — sim baseline;sdk_kind="open",hal.sim="openral_hal.g1:G1MujocoHAL"+hal.real=None(sim-only until M2). All MuJoCo wiring (MJCF URI, floating-base joint offsets) lives inG1_DESCRIPTION.sim. Drift-guarded againstrobots/g1/robot.yamlbytests/unit/test_robot_manifests_match_hal_constants.py.
python/hal/src/openral_hal/so100_mujoco.py
MuJoCo digital twin for the SO-100 follower arm (Menagerie MJCF).
class SO100MujocoHAL(MujocoArmHAL)— SO-100 follower MuJoCo HAL, driving themujoco_menagerietrs_so_arm100/so_arm100.xmlwith the same 6-DoF action layout asSO100FollowerHAL. Maps the lerobot-style description joint names to the Menagerie joints (shoulder_pan→Rotation, …,gripper→Jaw) and normalises the revolute Jaw range[-0.174, 1.75]to[0, 1]. Thin manifest-driven wrapper (ADR-0023);__init__forwards toself._init_from_description(SO100_DESCRIPTION, …). (L68)__init__(*, mjcf_path=None, settle_steps=1, gravity_enabled=True, staleness_limit_s=0.5)(L108)_read_gripper_normalised() -> float— Override that offsets the closed position from-0.174rad (the base helper assumes closed at qpos == 0).
python/hal/src/openral_hal/so100_sim.py
SO100DigitalTwin — in-process simulator for the SO-100 follower arm.
class SO100DigitalTwinConfig(RobotConfig)— Config for the digital twin. (L59) field:initial_positionsclass SO100DigitalTwin(Robot)— In-process digital twin. (L76)__init__(config)(L101)observation_features() -> dict[str, type]— One float per joint pos. (L116)action_features() -> dict[str, type]— One float per target. (L125)is_connected -> bool[@property] (L134)is_calibrated -> bool[@property] — Always True. (L139)connect(calibrate=True) -> None— Activate (no serial port opened). (L146)calibrate() -> None— No-op. (L154)configure() -> None— No-op. (L158)get_observation() -> RobotObservation— Lerobot-native units. (L162)send_action(action) -> RobotAction— Apply position cmd, update state. (L175)disconnect() -> None— Deactivate (idempotent). (L194)
python/hal/src/openral_hal/ros_control.py
RosControlHAL — ros2_control-backed HAL adapter.
class RosControlHAL—ros2_control-backed HAL adapter. (L72)__init__(description, controller_name, *, joint_state_topic='/joint_states', command_topic=None, publish_fn=None, state_fn=None, staleness_limit_s=0.5)(L101)connect() -> None(L132)disconnect() -> None(L150)read_state() -> JointState(L162)send_action(action) -> None— Publish JointTrajectory. (L199)estop() -> None(L230)- private:
_require_connected,_validate_action _default_publish(topic, msg) -> None— No-op publish when no real ROS 2 node. (L62)
python/hal/src/openral_hal/sim_transport.py
SimTransport — in-memory simulated ros2_control transport.
class SimTransport— In-memory transport simulating a JointTrajectory controller. (L32)__init__(n_joints)(L63)publish(topic, msg) -> None— Record msg, applyjoint_targets. (L73)state() -> dict[str, object]— Current simulated joint state. (L91)call_count -> int[@property] (L107)last_call -> tuple | None[@property] (L112)calls -> list[tuple][@property] (L117)
python/hal/src/openral_hal/lifecycle.py
Generic ROS 2 managed lifecycle node wrapper for every HAL adapter — UR5e / UR10e / Franka / SO-100 / OpenArm / H1 / future HALs all share the same publish / subscribe / heartbeat / OTel-span wiring.
class HALLifecycleNodeBase(LifecycleNode)— Public base class. Owns the standard/joint_states+~/joint_statespublishers, the/openral/safe_action+/openral/estopsubscribers (ADR-0018 F1/F5), the 1 HzDiagnosticsHeartbeat, the per-tickhal.read_state+hal.send_actionOTel spans, the estop latch, and the full configure → activate → deactivate → cleanup → shutdown transition wiring. The pre-ADR-0018~/command(trajectory_msgs/JointTrajectory) subscriber + its_on_commandcallback + the_subscriberfield were removed;_send_action_tracedis now driven only by_on_safe_action. (L322)_create_hal(self) -> HAL— Subclass hook (required): construct and return a HAL instance. Reads ROS-parameter-driven constructor args viaself.get_parameter(...). (L380)_heartbeat_extra_fields(self) -> dict[str, str]— Subclass hook (optional): extra key/values for the/diagnosticspayload (e.g.{"port": "/dev/ttyUSB0"}for SO-100,{"mjcf": "..."}for OpenArm). Default:{}. (L392)on_configure_post_hal(self) -> TransitionCallbackReturn— Subclass hook (optional): robot-specific setup after the HAL connects (e.g. opening a camera renderer on OpenArm). Default:SUCCESS. (L404)on_activate_post_subs(self) -> TransitionCallbackReturn— Subclass hook (optional): robot-specific timers/publishers after the base wires its subs (e.g. the OpenArm camera-render timer). Default:SUCCESS. (L413)on_deactivate_pre_teardown(self) -> None— Subclass hook (optional): stop robot-specific timers before base teardown. Default: no-op. (L421)on_cleanup_pre_disconnect(self) -> None— Subclass hook (optional): tear down robot-specific resources (viewers, renderers) before HAL.disconnect(). Default: no-op. (L428)_publish_joint_state(self) -> None— Timer callback. Wrapsself._hal.read_state()in ahal.read_statespan (identity attrs +producer.record_joint_state) and publishes the standard/joint_states+~/joint_statesmessages. Subclasses may override + callsuper()._publish_joint_state()to extend (OpenArm does this for viewer-sync). (L731)_on_safe_action(self, msg) -> None—/openral/safe_actioncallback (ADR-0018 F1/F5). Decodes theopenral_msgs/ActionChunkinto anopenral_core.Actionand forwards through_send_action_traced(action, source="safe_action"). (L795)_send_action_traced(self, action, *, source) -> None— Forwardactiontoself._hal.send_actioninside ahal.send_actionspan. Thesourceattribute disambiguates the origin on the dashboard's Commands card (kept on the span so future subscriber additions can fan in without changing the span shape). (L815)make_lifecycle_main(node_name, hal_factory) -> Callable[[], None]— Build amain()entry point for a zero-parameter HAL adapter. Internally constructs a_FactoryHALLifecycleNode(HALLifecycleNodeBase)whose_create_hal()returnshal_factory(). Superseded for the standard arms bymake_lifecycle_main_from_manifest(ADR-0032); retained for bespoke nodes. (L194)class ManifestHALLifecycleNode(HALLifecycleNodeBase)— Public generic manifest-driven lifecycle node (ADR-0032; promoted from the private_ManifestHALLifecycleNodeunder issue #191). Readsrobot_yaml+hal_mode+ sensor knobs as ROS params and builds its HAL viaopenral_hal.build_hal, so a robot's construction kwargs come from the manifest'shal.parameters.defaults(ADR-0029) — no bespoke_create_halsubclass. AttachesSimSensorBridge(cameras / depth / scan / viewer) inon_activate_post_subs. Inon_configure_post_hal, reflects on the built HAL and opens/openral/<robot>/reset_to_pose(openral_msgs/srv/ResetToPose) iff it exposesreset_to_pose— generalising the openarm-only service to everyMujocoArmHALsim arm (ADR-0029 blocker #4, issue #191 Phase 2); HALs without the method (panda_mobile, scene-attached twins) get no service. In_create_hal, when the manifest declaresscene_defaults.composition(and not scene-attaching), calls the named composer and threads the composed MJCF in as the HAL'smjcf_path(issue #191 Phase 3b — openarm tabletop). Inon_activate_post_subs, when the manifest declares a planar base (base_joints), also attaches aMobileBaseBridge(/odom+odom->base_linkTF +/cmd_vel→BODY_TWIST) — so panda_mobile runs on this node with no subclass (issue #191 Phase 3a). The per-robot lifecycle packages collapse into this node (issue #191 Phases 2-3). A back-compat alias_ManifestHALLifecycleNodeis retained. (L913)make_lifecycle_main_from_manifest(node_name) -> Callable[[], None]— Build amain()that spins upManifestHALLifecycleNode(ADR-0032). The node readsrobot_yaml+hal_mode("sim"|"real") ROS params and constructs its HAL viaopenral_hal.build_hal(description, mode=hal_mode)— one node class serves both modes for every robot. Used by franka / ur5e / ur10e / aloha / g1 / h1 / rizon4 / so100 / so101 (issue #191 Phase 2 migrated so100/so101 off their bespoke node);openral deploy siminjectshal_mode="sim",openral deploy run(ADR-0032) injectshal_mode="real". A robot lacking the requested mode raisesROSCapabilityMismatch. (L252)decode_action_chunk(msg) -> Action | None— Inverse ofros_publishing_hal._flatten_action_payload. Decodes the ADR-0028bActionChunkwire shape (flat+n_dof+horizon+control_mode) back into a typedopenral_core.Actionwith the per-mode payload field populated (cartesian_delta/gripper/body_twist/joint_*). ReturnsNonefor degenerate chunks (flat=[],n_dof≤0) and for modes the F1/F5 publisher doesn't encode (CARTESIAN_POSE,FOOT_PLACEMENT,DEX_HAND_JOINT). Used byHALLifecycleNodeBase._on_safe_action; lives at module scope so unit tests intests/unit/test_lifecycle_action_chunk_decoder.pyexercise it without a ROS 2 install. (L103)
python/hal/src/openral_hal/sim_bringup.py
Resolve a SimScene or BenchmarkScene YAML path to a live SimRollout. Used by build_hal (ADR-0034), which every manifest-driven node (incl. panda_mobile, issue #191 Phase 3) routes through.
build_sim_env_from_yaml(sim_env_yaml: str, *, robot_id_fallback: str | None = None) -> tuple[SimRollout, int | None]— Load aSimSceneorBenchmarkSceneYAML, resolve its scene id inopenral_sim.SCENES, and instantiate the env. Relative paths are resolved by walking parents of the source file (ROS param values are cwd-naïve). Returns(env, seed)— the caller plumbs the seed intoSimAttachedHAL(env_reset_seed=seed). RaisesROSConfigErrorwhen the YAML is not found, the scene id is unregistered, or schema validation fails. Robocasa scenes haveignore_done=Trueinjected so deploy-sim continuous stepping does not trip the episode-done guard; strict-validation native backends (e.g.tabletop_push) are unchanged. (L173)
python/hal/src/openral_hal/sim_attached.py
SimAttachedHAL — generic HAL Protocol adapter that wraps any in-process SimRollout (ADR-0025 Stage 3, ADR-0034). Shared by panda_mobile, manifest-driven arms, and tests; not import-safe without openral_sim + mujoco.
ActionPacker— Type aliasCallable[[Action, RobotDescription, int], np.ndarray]. Per-composition translator between an OpenRALActionand the env's flat action vector; the default factory ispack_action_for_env. Pass a custom instance toSimAttachedHAL.__init__for whole-body humanoid or dexterous-hand action layouts. (L165)normalized_joint_index(model_joint_names: list[str]) -> dict[str, int]— Map MJCF joint names (exact + robosuite-prefix-stripped) to model index (ADR-0034 §3.6). Exact names always win;robot0_joint1→joint1(strip^[a-z]+[0-9]+_) is added only when it neither shadows an exact name nor collides (bimanualrobot0_/robot1_ambiguity → keep explicit). Used bySimAttachedHAL.read_stateso one manifest serves both native MjSpec and robosuite scenes;robot0_never appears in a manifest. (L116)is_terminated_episode_error(exc: BaseException) -> bool— True iffexcis robosuite's post-terminal step guard (ValueError("executing action in terminated episode"),environments/base.py), matched by message substring (case-insensitive, stable across robosuite releases). Raw-robosuite backends (libero_custom_bddl,so100_robosuite;ignore_done=False) HARD-RAISE this instead of returning a terminalStepResult;SimAttachedHAL._step_and_cachekeys its raised-terminal recovery (reset + re-step) off this predicate so deploy-sim's continuous twin keeps driving. Any otherstepfault returnsFalseand propagates (never silently swallowed). ADR-0036 (amended). (L98)pack_action_for_env(action: Action, description: RobotDescription, env_action_dim: int) -> np.ndarray— DefaultActionPacker. TranslatesJOINT_POSITION(arm-only or full base+arm),BODY_TWIST(vx/vy/wz → slots 0-2),CARTESIAN_DELTA(6-vec → arm slots[base_dim:]), andGRIPPER_POSITION(→ last slot) into the env's flat action vector. RaisesROSConfigErrorfor unsupported modes or mismatched row widths. (L168)class SimAttachedHAL— HAL Protocol adapter wrapping an in-processSimRollout. Reads live joint state vianormalized_joint_index+mj_name2id; sends actions viapack_action_for_env(or a caller-suppliedActionPacker) intoenv.step(). Exposesread_images(),mujoco_handles(),sim_time_ns(),base_pose,base_twist,base_pose_6dof()for the ROS lifecycle node's camera publisher, viewer, sim-clock, and odom wiring. (L327)__init__(env: SimRollout, description: RobotDescription, *, action_packer: ActionPacker | None = None, env_reset_seed: int | None = None, env_action_dim: int | None = None, body_twist_dt_s: float = 0.05) -> None(L356)connect() -> None— Reset the env atenv_reset_seed; probeenv_action_dim(via_probe_env_action_dim, which raisesROSConfigErrornaming the backend when noaction_dimis introspectable and no override was given — never a silent fallback); invalidate joint-index cache. Idempotent. (L453)disconnect() -> None— Release env handle (idempotent). (L525)read_state() -> JointState— Walkdescription.joints, resolve each joint vianormalized_joint_index, read liveqpos/qvelfrom MJCF. (L529)send_action(action: Action) -> None— Pack action via composite-split orActionPacker; callenv.step.BODY_TWISTtakes a direct-qpos Euler-integration path on a MuJoCo backend (_apply_body_twist_to_qpos, skipsenv.stepso the arm doesn't churn); on a non-MuJoCo backend (Isaac kinematic base, ADR-0045) it routes through_apply_body_twist_via_env_stepinstead — the scene integrates the base insideenv.step. Stampslast_action_nsat the top (the single choke point both_on_safe_actionand_on_cmd_velreach) so the idle stepper yields to it. Routes the step through_step_and_cache, which auto-resets on episode termination — both the returned terminal (StepResult.terminated/truncatedlatched as_episode_done) and a raised terminal (raw-robosuiteignore_done=Falsebackends throwingis_terminated_episode_error); the raised path resets once and re-steps so deploy-sim never freezes with the "env.step failed: executing action in terminated episode" spam. ADR-0036 (amended). (L603)idle_step() -> bool— Sim-only free-running stepper (ADR-0034 2026-06-04 amendment). Advances the wrappedSimRolloutone tick withnp.zeros(env_action_dim)(HOLD) so cameras keep rendering when no skill is executing — without it an idle deploy-sim scene freezes and the ADR-0035 perception bus sees a dead scene. ReturnsFalse(suppressed) when not connected, estop-latched,env_action_dim is None, or no live MuJoCo handles; else steps and returnsTrue. Mirrorssend_action's ADR-0036 deferred-reset branch and_last_obsre-cache; does NOT touch_last_env_action/_last_body_twist. Defined ONLY onSimAttachedHAL— real HALs never define it; this method-only exclusion (not "zero is harmless") is the primary real-hardware guard, since a zero vector is a HOLD in sim but "drive to 0 rad" on a real position arm. (L826)read_images() -> dict[str, Any]— Return latest rendered camera frames keyed by camera name from the cached_last_obs. (L1364)read_depth_clouds() -> dict[str, NDArray]— Per-depth-sensor(N,3)base_linkpoint clouds from_last_obs["depth_points"](a non-MuJoCo backend, e.g. the Isaac scene, deprojects viaCamera.get_pointcloudso the HAL never re-derives geometry);{}when the backend renders no depth.SimSensorBridgepublishes them asPointCloud2for octomap. (ADR-0045)read_scan() -> NDArray | None— The 2-D LaserScan range fan (base_link,angle_min=-π→+π) from_last_obs["scan"]when a non-MuJoCo backend ray-casts a lidar (the Isaac scene, ADR-0045);Nonewhen it renders no lidar.SimSensorBridge._compute_scan_rangesreads it for/scan. (ADR-0045)mujoco_handles() -> tuple[Any, Any] | None— Forward the env's(model, data)MJCF handles. (L1260)sim_time_ns() -> int | None— Cross-reset-monotonic elapsed sim time in ns (ADR-0048 Phase 1) — the seam a sim/clockpublisher reads. Returns the wrappedSimRollout.sim_time_ns()(per-episode) plus an accumulated offset:connectand the ADR-0036 auto-resets fold each finished episode's elapsed sim-time into the offset (_accumulate_sim_time_before_reset) BEFORE the backend rewinds its clock, so the value is monotonic non-decreasing acrossenv.reset(robocasa rewindsMjData.timeto 0).Nonewhen the wrapped rollout has no sim clock (clock-less backend / sidecar) — the consumer then falls back to wall time.estop() -> None— Latch e-stop; subsequentsend_actioncalls are dropped. (L1254)base_pose -> tuple[float, float, float][@property] — Current(x, y, yaw): from MJCF qpos on a MuJoCo backend, else fromobs["base_pose"]the SimRollout surfaces (Isaac kinematic base, ADR-0045);(0,0,0)when the backend reports neither. Feeds the/odompublisher. (L1428)base_twist -> tuple[float, float, float, float, float, float][@property] — Last commanded body twist(vx, vy, vz, wx, wy, wz). (L1481)_apply_body_twist_via_env_step(row: list[float]) -> None— Non-MuJoCoBODY_TWIST: validate the planar twist, latch it for/odom, pack(vx, vy, wz)into the FINAL three env-action slots (the manifest scene's[arm…, gripper, base-twist]layout), zero the arm/gripper so a pure base move holds the arm, and_step_and_cache. (ADR-0045)base_pose_6dof() -> tuple[...] | None— Full 6-DoF(xyz, quat_xyzw)from robocasaraw_proprio; falls back toNonefor non-robocasa backends. (L1491)last_action_ns -> int[@property] — Monotonic ns of the last real action throughsend_action;0until the first one. The idle stepper reads it (viashould_idle_step) to yield to an active skill. (L1354)
python/hal/src/openral_hal/sim_sensor_bridge.py
Shared sim-sensor + viewer bridge for scene-attached HAL lifecycle nodes (ADR-0034). Republishes RGB camera frames and a live MuJoCo viewer for any manifest-driven node, and runs the sim-only idle stepper. Phase 2 adds /scan + depth PointCloud2. Depth comes from the MuJoCo ray-cast (_publish_depth_clouds) OR, for a non-MuJoCo backend that surfaces ready base_link clouds in obs (the Isaac scene, ADR-0045), _publish_depth_clouds_from_obs — which wraps hal.read_depth_clouds() into a base_link PointCloud2 (no ray-cast, no per-camera optical TF); _setup_depth creates the publishers when either source is present. rclpy imported lazily.
should_idle_step(now_ns: int, last_action_ns: int, idle_hold_ns: int) -> bool— Pure predicate (no rclpy) for the sim-only idle stepper:Trueiffnow_ns - last_action_ns >= idle_hold_ns— i.e. no real action arrived within the idle-hold window, so the stepper may HOLD-step the env. Used bySimSensorBridge._idle_step_tick; unit-testable in isolation. (ADR-0034 2026-06-04 amendment) (L48)constant_scan_no_hit_ranges(*, n_beams: int, max_range_m: float) -> list[float]— Pure (no rclpy) synthetic/scanfan: every beam clamped tomax_range_m("no hit everywhere"), the honest reading for an in-process digital twin with no scene to ray-cast. Used bySimSensorBridge._compute_scan_ranges's no-handles branch; moved out of the panda_mobile node in issue #191 Phase 3. (sim_sensor_bridge.py)class SimSensorBridge— Wire and tear down sim-sensor publishers and the MuJoCo viewer on a HAL lifecycle node. Streams are gated on the robot manifest + HAL capability. Owns/scanfor both paths since issue #191 Phase 3: live MJCF ray-cast whenhal.mujoco_handles()is bound (SimAttachedHAL), aconstant_scan_no_hit_rangesfan for the bare digital twin (the node no longer publishes its own scan). (L118)__init__(node: Any, hal: Any, description: RobotDescription, *, viewer_enabled: bool = True, camera_rate_hz: float = 10.0, viewer_sync_rate_hz: float = 30.0, scan_rate_hz: float = 10.0, scan_n_beams: int = 360, scan_max_range_m: float = 12.0, scan_min_range_m: float = 0.05, depth_rate_hz: float = 10.0, depth_max_range_m: float = 5.0, depth_pixel_stride: int = 4, idle_hold_ms: float = 200.0, on_step: Any = None) -> None—on_step(ADR-0049): optional zero-arg callback invoked after each successfulidle_step(the node refreshes the proprio snapshot through it, so odom/joint_state stay fresh while idle). (L135)setup() -> None— Activate all streams the manifest + HAL support: RGB camera publishers on/openral/cameras/<n>/image(gated onhasattr(hal, "read_images")+ RGBSensorSpec), the sim-only idle stepper (gated oncallable(getattr(hal, "idle_step", None))+ live MuJoCo handles), viewer (mujoco.viewer.launch_passivewithshow_left_ui=False, show_right_ui=Falseso only the sim renders;_aim_viewer_camerathen sets the opening free-camera pose viainitial_viewer_camera— eye at a 3rd-person scene camera, orbit pivot on the base, base-aligned default for camera-less twins — leaving the cameramjCAMERA_FREEso the user can orbit/zoom; GL/DISPLAY failure → warn + continue). Idempotent per activate. (L215)teardown() -> None— Cancel timers (incl. the idle-step timer), destroy publishers, close viewer. Called fromon_deactivate/on_cleanup. (L223)quaternion_from_yaw(yaw: float) -> tuple[float, float, float, float]— Pure(x, y, z, w)quaternion for a yaw-only rotation. Used byMobileBaseBridge._publish_odomfor the Odometry orientation + TF; moved out of the panda_mobile node in issue #191 Phase 3. (mobile_base_bridge.py)class MobileBaseBridge— Generic planar-mobile-base ROS wiring (sibling ofSimSensorBridge): owns/odom, theodom->base_linkTF, and the/cmd_vel→BODY_TWIST bridge (ADR-0024 out-of-scope: bypasses the safety supervisor; Nav2'svelocity_smoothercaps velocity). Frame ids come fromRobotDescription.{odom_frame,base_frame}; the HAL must exposebase_pose(base_pose_6dof()/base_twistused when present).ManifestHALLifecycleNodeattaches it inon_activate_post_subsiff the manifest declaresbase_joints— so a mobile robot needs no node subclass (issue #191 Phase 3, replaced the bespoke panda_mobile node). (mobile_base_bridge.py)__init__(node, hal, description, *, odom_rate_hz: float = 20.0, cmd_vel_topic: str = "/cmd_vel", proprio: Any = None) -> None—proprio(ADR-0049): when set (sim-attached HALs), odom is published from the node's dedicated thread viapublish_from_snapshot, reading the snapshot not the simulator;None(real HALs) keeps the legacy odom timer.setup() -> None— Create the/odompublisher + TF broadcaster +/cmd_velsubscription; the odom timer is created only whenproprio is None(ADR-0049 — sim HALs publish odom off the node's thread).publish_from_snapshot() -> None— ADR-0049 dedicated-thread entry: publish one/odom+ TF sample from the proprio snapshot (never the simulator). Thin alias over_publish_odom(which branches onproprio).teardown() -> None— Cancel the timer (if any) + destroy the publisher/subscription. Idempotent.
python/hal/src/openral_hal/proprio_snapshot.py
ADR-0049 — decouples the control-critical publishers (odom / joint_state / TF) from the single executor thread that runs env.step + render + raycast. The sim-attached HAL node captures a frame after each step (on the executor thread, where reading the sim is safe) and a dedicated publisher thread re-emits it at ~30 Hz, so odom stays fresh (~28 Hz live, vs ~1.8 Hz starved) without ever touching MjData/GL off the executor thread (a MultiThreadedExecutor was rejected — MuJoCo's GL context is thread-affine).
class ProprioFrame— Frozen dataclass: one coherent proprio sample (state: JointState,base_pose: (x,y,yaw),base_pose_6dof: ((x,y,z),(qx,qy,qz,qw)) | None,base_twist: tuple[float, ...],sim_time_ns: int | None— ADR-0048 Phase 2, sim time carried for the /clock publisher). Plain immutable data only — no live simulator handles — so it is safe to publish from a different thread than the one that stepped the sim. (proprio_snapshot.py)class ProprioSnapshot— Lock-guarded holder for the latestProprioFrame. One writer (the executor thread, after each step) callsset; readers (the publisher thread) calllatest; the immutable frame is swapped under the lock so a reader never sees a torn frame and never reaches the HAL. HAL-agnostic — the node does the capture. (proprio_snapshot.py)set(frame: ProprioFrame) -> None— Atomically publishframeas the latest sample (executor thread only). (proprio_snapshot.py)latest() -> ProprioFrame | None— Return the most recent frame, orNonebefore the first capture. (proprio_snapshot.py)