Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Scalar Joint with 3D Path (Curved Rail/Track Support) #2452

Open
ekchapman opened this issue Feb 24, 2025 · 1 comment
Open

Scalar Joint with 3D Path (Curved Rail/Track Support) #2452

ekchapman opened this issue Feb 24, 2025 · 1 comment
Labels
enhancement New feature or request

Comments

@ekchapman
Copy link

ekchapman commented Feb 24, 2025

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
<mujoco model="rail">
<worldbody>
  <light name="main_light" pos="0 3 5" dir="-.25 -1 -1" diffuse=".7 .7 .8"
    specular="0.3 0.3 0.3" directional="true" />
  <light name="side_light" pos="2 2 1" dir="-1 -1 -1" diffuse="0.7 0.7 0.8"
    specular="0.2 0.2 0.2" />
  <geom name="floor" type="plane" size="50 50 0.1" pos="0 0 0" />

  <!-- The rail car is technically free in translation. -->
  <body name="rail-car" pos="0 0 .5">
    <geom type="sphere" size="0.1" density="1000" rgba=".2 .2 1 1" />
    <joint name="slider_x" type="slide" axis="1 0 0" damping="1000" />
    <joint name="slider_y" type="slide" axis="0 1 0" damping="1000" />
    <joint name="slider_z" type="slide" axis="0 0 1" damping="1000" />

    <!-- Give the sim a bit of character... A hanging rollercoaster? -->
    <body name="payload" pos="0 0 -0.2">
      <geom type="box" size="0.1 0.1 0.1" rgba=".2 1 .2 1" />
      <joint name="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. -->
  <body name="joystick" pos="0 0 .1">
    <joint name="dummy_joint" type="slide" axis="1 0 0" damping="1000" />
    <geom type="sphere" size="0.01" rgba="1 .2 .2 1" />
  </body>
</worldbody>

<actuator>
  <!-- This lets us pass a scalar input "j" into mujoco.simulate... -->
  <position name="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} -->
  <position name="actuator_x" joint="slider_x" kp="10000" />
  <position name="actuator_y" joint="slider_y" kp="10000" />
  <position name="actuator_z" joint="slider_z" kp="10000" />
</actuator>

</mujoco>
python
import mujoco
import mujoco.viewer
import numpy as np
import time
import os

PATH = os.path.join(os.path.dirname(__file__), 'rail.xml')

def helix(j):
    """This could be any scalar -> 3D mapping. Here we use a helix."""
    theta = 2 * np.pi * j * 2
    x = np.cos(theta)
    y = np.sin(theta)
    z = 0.5 * j
    return np.array([x, y, z])

model = mujoco.MjModel.from_xml_path(PATH)
data = mujoco.MjData(model)

viewer = mujoco.viewer.launch_passive(model, data)

while viewer.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

@ekchapman ekchapman added the enhancement New feature or request label Feb 24, 2025
@jjyyxx
Copy link
Contributor

jjyyxx commented Feb 25, 2025

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.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request
Projects
None yet
Development

No branches or pull requests

2 participants