You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I propose a joint type that creates motion DoFs along a 3D path, similar to a roller coaster rail, bead maze, or curved robot 7th axis. This would allow 1-DoF movement along arbitrary curved trajectories without having application-side logic to implement it.
If not in the kinematic tree, this feature would also be super helpful if implemented as a constraint.
Alternatives
Currently, I implement this behavior with an under-constrained body and actuator control. This introduces additional gain tuning and also requires the model to be developed in Python (or c++) instead of in simulate. Nor does it guarantee strict adherence to the path as a kinematic constraint would.
<mujocomodel="rail">
<worldbody>
<lightname="main_light"pos="0 3 5"dir="-.25 -1 -1"diffuse=".7 .7 .8"specular="0.3 0.3 0.3"directional="true" />
<lightname="side_light"pos="2 2 1"dir="-1 -1 -1"diffuse="0.7 0.7 0.8"specular="0.2 0.2 0.2" />
<geomname="floor"type="plane"size="50 50 0.1"pos="0 0 0" />
<!-- The rail car is technically free in translation. -->
<bodyname="rail-car"pos="0 0 .5">
<geomtype="sphere"size="0.1"density="1000"rgba=".2 .2 1 1" />
<jointname="slider_x"type="slide"axis="1 0 0"damping="1000" />
<jointname="slider_y"type="slide"axis="0 1 0"damping="1000" />
<jointname="slider_z"type="slide"axis="0 0 1"damping="1000" />
<!-- Give the sim a bit of character... A hanging rollercoaster? -->
<bodyname="payload"pos="0 0 -0.2">
<geomtype="box"size="0.1 0.1 0.1"rgba=".2 1 .2 1" />
<jointname="ball_joint"type="ball"pos="0 0 0.1"damping=".1" />
</body>
</body>
<!-- A dummy body to be our "joystick", i.e. scalar control signal. -->
<bodyname="joystick"pos="0 0 .1">
<jointname="dummy_joint"type="slide"axis="1 0 0"damping="1000" />
<geomtype="sphere"size="0.01"rgba="1 .2 .2 1" />
</body>
</worldbody>
<actuator>
<!-- This lets us pass a scalar input "j" into mujoco.simulate... -->
<positionname="joystick"joint="dummy_joint"kp="10000"ctrlrange="0 1" />
<!-- And then in our sim code we'll retrieve "j" and set the following 3 dofs to f(j) = {3D coordinates along trajectory} -->
<positionname="actuator_x"joint="slider_x"kp="10000" />
<positionname="actuator_y"joint="slider_y"kp="10000" />
<positionname="actuator_z"joint="slider_z"kp="10000" />
</actuator>
</mujoco>
python
importmujocoimportmujoco.viewerimportnumpyasnpimporttimeimportosPATH=os.path.join(os.path.dirname(__file__), 'rail.xml')
defhelix(j):
"""This could be any scalar -> 3D mapping. Here we use a helix."""theta=2*np.pi*j*2x=np.cos(theta)
y=np.sin(theta)
z=0.5*jreturnnp.array([x, y, z])
model=mujoco.MjModel.from_xml_path(PATH)
data=mujoco.MjData(model)
viewer=mujoco.viewer.launch_passive(model, data)
whileviewer.is_running():
target_pos=helix(data.actuator("joystick").ctrl.item())
data.actuator("actuator_x").ctrl=target_pos[0]
data.actuator("actuator_y").ctrl=target_pos[1]
data.actuator("actuator_z").ctrl=target_pos[2]
mujoco.mj_step(model, data)
viewer.sync()
time.sleep(model.opt.timestep)
Screencast.from.02-24-2025.01.01.24.PM.webm
Additional context
No response
The text was updated successfully, but these errors were encountered:
I would love to see this feature implemented. While it may not fit as generalized coordinates, I agree that it suits the form of constraints.
In my opinion, this represents a generalization of <equality/joint> that spans multiple joints and can include non-linear equality constraints. More generally, I believe it would be beneficial to introduce a new plugin capability for computing custom constraints, conceptually similar to the passive force plugin but more complex. Currently, all constraints are allocated, computed, and finalized in mj_makeConstraint, which makes it challenging to integrate custom constraints into the process.
The feature, motivation and pitch
I propose a joint type that creates motion DoFs along a 3D path, similar to a roller coaster rail, bead maze, or curved robot 7th axis. This would allow 1-DoF movement along arbitrary curved trajectories without having application-side logic to implement it.
If not in the kinematic tree, this feature would also be super helpful if implemented as a constraint.
Alternatives
Currently, I implement this behavior with an under-constrained body and actuator control. This introduces additional gain tuning and also requires the model to be developed in Python (or c++) instead of in
simulate
. Nor does it guarantee strict adherence to the path as a kinematic constraint would.rail.zip
mjcf model
python
Screencast.from.02-24-2025.01.01.24.PM.webm
Additional context
No response
The text was updated successfully, but these errors were encountered: