Joint equality constraint between multiple input and output joints #2413
-
IntroHi! I am a PhD student at Arizona State University, I use MuJoCo for my research on co-designing a robot's mechanism and control. My setupMuJoCo 3.2.7, Python 3.11.11, Windows 11 Pro 23H2 My questionCurrently, MuJoCo supports joint equality constraint that allows the coupling of an input and an output joint with an arbitrary quartic polynomial. This is an interesting feature because I can then directly optimize the polynomial without worrying about the actual mechanism. For example, I can build a simple jumping model and find the best polynomial that achieve the highest jump. Once the optimum coupling is found, I can then try to find a mechanism that realize it. However, the current joint constraint only supports one input coupled to one output. I am more interested in extending this idea to multiple inputs and outputs. For example, I want to study what is the best coupling between two input joints and the 2D motion of the foot to achieve let's say the fastest forward running. My question is: how can I achieve this arbitrary coupling between multiple input and output joints within MuJoCo? After reading through the documentation about the constraint model and constraint solver and a little bit of the source code for instantiating the joint equality constraint, it seems that it comes down to supplying the residual and derivative of the constraint and the constraint solver should be able to handle it. There are probably lots of details to consider. I would like to hear about your thoughts and suggestions. Do I have to add some custom code to the source code to achieve this? Are there any simpler ways? Thank you so much. Minimal model and/or code that explain my questionMy question is not really related to any specific code, but I am attaching the code for the jumping example to better demonstrate the idea. This model should just work with the default viewer: You can adjust the input angle in the viewer and the foot will move accordingly. The interesting thing is that by changing the polynomial coefficient, I can modify the jumping behavior without worrying about the actual mechanism. <mujoco>
<option timestep="0.0005" gravity="0 0 -9.81" integrator="implicit">
</option>
<default>
<geom solref="0.002 1" contype="0" />
<joint solreflimit="0.002 1" />
<equality solref="0.002 1" />
</default>
<worldbody>
<geom name="floor" type="plane" size="0 0 1" rgba="0.9 0.9 0.9 1" contype="1" />
<body name="body" pos="0 0 0.5">
<joint name="body" type="slide" axis="0 0 1" />
<!-- <freejoint /> -->
<light mode="track" pos="0 0 3" directional="true" />
<geom name="body" type="box" size="0.05 0.05 0.05" rgba="0 0 1 0.5" />
<body name="input" pos="0 0 0">
<joint name="input" type="hinge" axis="0 1 0" damping="1" />
<geom name="input" type="box" size="0.025 0.01 0.01" pos="0.025 0 0"
rgba="1 0 0 1" />
</body>
<body name="foot" pos="0 0 0">
<joint name="foot" type="slide" axis="0 0 1" damping="10" />
<geom name="foot" type="sphere" size="0.02" rgba="0 1 0 1" />
</body>
</body>
</worldbody>
<actuator>
<position name="input" joint="input" kp="100" />
</actuator>
<equality>
<joint name="foot" joint1="input" joint2="foot" polycoef="0 -3 0 0 0" />
</equality>
</mujoco> Confirmations
|
Beta Was this translation helpful? Give feedback.
Replies: 1 comment 2 replies
-
Using the current API you have two options:
I think option 2 will give you what you want. |
Beta Was this translation helpful? Give feedback.
Using the current API you have two options:
I think option 2 will give you what you want.