robosuite Jaco arm default pose violates three joint limits by up to 65°
In the Jaco robot MJCF bundled with robosuite
(robosuite/models/assets/robots/jaco/robot.xml), the default qpos0 (the
reset state used when there are no keyframes) leaves three joints at 0 while
all three joints have strictly positive lower bounds. The worst violation is
j2s7s300_joint_6 = 0 versus range = [1.134, 5.149] — a 65° offset from
the declared lower limit.
MuJoCo loads the model without raising an error; the out-of-range joint values
are silently clamped on every mj_resetData() call.
Minimal reproduction
Run from a clean robosuite checkout:
git clone https://github.com/ARISE-Initiative/robosuite.git
cd robosuite
python -m pip install -e .
python -c "
import mujoco, pathlib
xml = pathlib.Path('robosuite/models/assets/robots/jaco/robot.xml')
model = mujoco.MjModel.from_xml_path(str(xml))
data = mujoco.MjData(model)
mujoco.mj_resetData(model, data)
mujoco.mj_forward(model, data)
bad = []
for jid in range(model.njnt):
if not model.jnt_limited[jid]:
continue
if int(model.jnt_type[jid]) not in (
int(mujoco.mjtJoint.mjJNT_HINGE),
int(mujoco.mjtJoint.mjJNT_SLIDE),
):
continue
qid = int(model.jnt_qposadr[jid])
value = float(data.qpos[qid])
lo, hi = map(float, model.jnt_range[jid])
if lo <= value <= hi:
continue
joint = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_JOINT, jid)
bad.append((max(lo - value, value - hi), joint, value, lo, hi))
bad.sort(reverse=True)
print('nkey:', model.nkey)
print('default-pose violations:', len(bad))
print('max excess (rad):', max((r[0] for r in bad), default=0.0))
for excess, joint, value, lo, hi in bad:
print(f'{joint}: value={value:.6g}, range=[{lo:.6g}, {hi:.6g}], excess={excess:.4g} rad ({excess*180/3.14159:.1f} deg)')
"
Observed output:
nkey: 0
default-pose violations: 3
max excess (rad): 1.13446
j2s7s300_joint_6: value=0, range=[1.13446, 5.14872], excess=1.134 rad (65.0 deg)
j2s7s300_joint_2: value=0, range=[0.820305, 5.46288], excess=0.8203 rad (47.0 deg)
j2s7s300_joint_4: value=0, range=[0.523599, 5.75959], excess=0.5236 rad (30.0 deg)
Expected
For every limited hinge/slide joint in the default reset state:
joint.range[0] <= qpos[joint.qposadr] <= joint.range[1]
Actual / impact
When robot.xml is loaded as a standalone MJCF, mj_resetData() initializes j2s7s300_joint_2, j2s7s300_joint_4, and j2s7s300_joint_6 at 0 rad, outside their declared ranges. The largest mismatch is joint_6, about 65° below its lower bound.
This does not appear to affect robosuite’s normal environment reset path, because the Jaco model defines an explicit init_qpos and Robot.reset() writes that value into sim.data.qpos. However, the bundled MJCF asset itself still exposes an internally inconsistent standalone default state. This can affect users who load the robot XML directly, build custom tasks from it, or assume that mj_resetData() produces a state satisfying the model’s declared joint limits.
Suggested fix
Set an explicit in-range standalone default for the affected joints, for example by adding ref values to j2s7s300_joint_2, j2s7s300_joint_4, and j2s7s300_joint_6, or by documenting/providing an explicit in-range keyframe for standalone use.
A natural choice would be to align the MJCF default with robosuite’s existing Jaco.init_qpos, since that configuration is already used by the environment-level reset path and is within the declared joint ranges. Alternatively, if 0 is intended to be a valid physical configuration for these joints, the declared ranges should be widened to include 0.
A regression test could load the standalone robot XML, call mj_resetData(), and assert that every limited hinge/slide joint satisfies range[0] <= qpos <= range[1].
robosuite Jaco arm default pose violates three joint limits by up to 65°
In the Jaco robot MJCF bundled with robosuite
(
robosuite/models/assets/robots/jaco/robot.xml), the defaultqpos0(thereset state used when there are no keyframes) leaves three joints at
0whileall three joints have strictly positive lower bounds. The worst violation is
j2s7s300_joint_6 = 0versusrange = [1.134, 5.149]— a 65° offset fromthe declared lower limit.
MuJoCo loads the model without raising an error; the out-of-range joint values
are silently clamped on every
mj_resetData()call.Minimal reproduction
Run from a clean robosuite checkout:
Observed output:
Expected
For every limited hinge/slide joint in the default reset state:
Actual / impact
When robot.xml is loaded as a standalone MJCF, mj_resetData() initializes j2s7s300_joint_2, j2s7s300_joint_4, and j2s7s300_joint_6 at 0 rad, outside their declared ranges. The largest mismatch is joint_6, about 65° below its lower bound.
This does not appear to affect robosuite’s normal environment reset path, because the Jaco model defines an explicit init_qpos and Robot.reset() writes that value into sim.data.qpos. However, the bundled MJCF asset itself still exposes an internally inconsistent standalone default state. This can affect users who load the robot XML directly, build custom tasks from it, or assume that mj_resetData() produces a state satisfying the model’s declared joint limits.
Suggested fix
Set an explicit in-range standalone default for the affected joints, for example by adding ref values to j2s7s300_joint_2, j2s7s300_joint_4, and j2s7s300_joint_6, or by documenting/providing an explicit in-range keyframe for standalone use.
A natural choice would be to align the MJCF default with robosuite’s existing Jaco.init_qpos, since that configuration is already used by the environment-level reset path and is within the declared joint ranges. Alternatively, if 0 is intended to be a valid physical configuration for these joints, the declared ranges should be widened to include 0.
A regression test could load the standalone robot XML, call mj_resetData(), and assert that every limited hinge/slide joint satisfies range[0] <= qpos <= range[1].