Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 14 additions & 0 deletions mujoco_warp/_src/derivative.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,14 @@ def _qderiv_actuator_passive_vel(
actuator_biastype: wp.array(dtype=int),
actuator_actadr: wp.array(dtype=int),
actuator_actnum: wp.array(dtype=int),
actuator_forcelimited: wp.array(dtype=bool),
actuator_gainprm: wp.array2d(dtype=vec10f),
actuator_biasprm: wp.array2d(dtype=vec10f),
actuator_forcerange: wp.array2d(dtype=wp.vec2),
# Data in:
act_in: wp.array2d(dtype=float),
ctrl_in: wp.array2d(dtype=float),
actuator_force_in: wp.array2d(dtype=float),
# Out:
vel_out: wp.array2d(dtype=float),
):
Expand All @@ -64,6 +67,14 @@ def _qderiv_actuator_passive_vel(
vel_out[worldid, actid] = 0.0
return

# skip if force is clamped by forcerange
if actuator_forcelimited[actid]:
force = actuator_force_in[worldid, actid]
forcerange = actuator_forcerange[worldid % actuator_forcerange.shape[0], actid]
if force <= forcerange[0] or force >= forcerange[1]:
vel_out[worldid, actid] = 0.0
return

vel = float(bias)
if actuator_dyntype[actid] != DynType.NONE:
if gain != 0.0:
Expand Down Expand Up @@ -256,10 +267,13 @@ def deriv_smooth_vel(m: Model, d: Data, out: wp.array2d(dtype=float)):
m.actuator_biastype,
m.actuator_actadr,
m.actuator_actnum,
m.actuator_forcelimited,
m.actuator_gainprm,
m.actuator_biasprm,
m.actuator_forcerange,
d.act,
d.ctrl,
d.actuator_force,
],
outputs=[vel],
)
Expand Down
70 changes: 70 additions & 0 deletions mujoco_warp/_src/derivative_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,76 @@ def test_step_tendon_serial_chain_no_nan(self):
self.assertFalse(np.any(np.isnan(mjd.qpos)))
self.assertFalse(np.any(np.isnan(mjd.qvel)))

def test_forcerange_clamped_derivative(self):
"""Implicit integration is more accurate than Euler with active forcerange clamping."""
xml = """
<mujoco>
<option timestep="0.01" integrator="implicitfast"/>
<worldbody>
<geom type="plane" size="10 10 0.001"/>
<body pos="0 0 1">
<joint name="slide" type="slide" axis="1 0 0"/>
<geom type="sphere" size="0.1" mass="1"/>
</body>
</worldbody>
<actuator>
<position joint="slide" kp="10000" kv="1000" forcerange="-10 10"/>
</actuator>
</mujoco>
"""

dt_small = 1e-4
dt_large = 1e-2
duration = 1.0
nsteps_large = int(duration / dt_large)
nsubstep = int(dt_large / dt_small)

# ground truth: Euler with small timestep
mjm_gt = mujoco.MjModel.from_xml_string(xml)
mjd_gt = mujoco.MjData(mjm_gt)
mjm_gt.opt.timestep = dt_small
mjm_gt.opt.integrator = mujoco.mjtIntegrator.mjINT_EULER
mujoco.mj_resetData(mjm_gt, mjd_gt)
mjd_gt.ctrl[0] = 0.5

# implicitfast at large timestep
mjm_impl, mjd_impl, m_impl, d_impl = test_data.fixture(xml=xml)
m_impl.opt.timestep.fill_(dt_large)
m_impl.opt.integrator = int(mujoco.mjtIntegrator.mjINT_IMPLICITFAST)
d_impl.ctrl.fill_(0.5)

# euler at large timestep
mjm_euler, mjd_euler, m_euler, d_euler = test_data.fixture(xml=xml)
m_euler.opt.timestep.fill_(dt_large)
m_euler.opt.integrator = int(mujoco.mjtIntegrator.mjINT_EULER)
d_euler.ctrl.fill_(0.5)

error_implicit = 0.0
error_euler = 0.0

for _ in range(nsteps_large):
# ground truth: small steps with Euler
mujoco.mj_step(mjm_gt, mjd_gt, nsubstep)

# implicit at large timestep
mjw.step(m_impl, d_impl)

# euler at large timestep
mjw.step(m_euler, d_euler)

# accumulate errors
gt_qpos = mjd_gt.qpos[0]
diff_implicit = gt_qpos - d_impl.qpos.numpy()[0, 0]
diff_euler = gt_qpos - d_euler.qpos.numpy()[0, 0]
error_implicit += diff_implicit * diff_implicit
error_euler += diff_euler * diff_euler

self.assertLess(
error_implicit,
error_euler,
"implicitfast should be more accurate than Euler at large timestep when forcerange derivatives are correctly handled",
)


if __name__ == "__main__":
wp.init()
Expand Down
Loading