How can I add the contraints of a custom five bar linkage in the XML file? #2662
Replies: 3 comments
-
Hello, I am a MuJoCo user, hope this helps.
You can load the model in simulate and move the control sliders to observe the movement. <mujoco model="5bar">
<compiler angle="radian"/>
<option integrator = "implicit" timestep = "0.002"
jacobian = "dense" cone = "elliptic"
solver = "Newton" tolerance="1e-10"/>
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="160" elevation="-20"/>
</visual>
<asset>
<texture type="skybox" builtin="gradient" rgb1=".3 .5 .7" rgb2="0 0 0" width="512" height="512"/>
<texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .2 .3" rgb2=".2 .3 .4"/>
<material name="grid" texture="grid" texrepeat="1 1" texuniform="true" reflectance=".2"/>
</asset>
<!-- Worldbody: the ground (plane) -->
<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true"/>
<geom name="floor" size="0.5 0.5 0.05" type="plane" material="grid"/>
<!-- Proximal link left side -->
<body name="l1_left" pos="0 0.0335 0.05">
<joint name="j1_left" type="hinge" pos="0 0 0" axis="0 0 1" range="-0.785 1.57" frictionloss="0.005"/>
<geom type="capsule" fromto="0 0 0 0.2 0 0" size="0.01" density="800" rgba="0 0.5 0.5 0.8"/>
<!-- Distal link left side -->
<body name="l2_left" pos="0.2 0 0">
<joint name="j2_left" type="hinge" pos="0 0 0" axis="0 0 1" frictionloss="0.005"/>
<geom type="capsule" fromto="0 0 0 0.19717 -0.0335 0" size="0.01" density="800" contype="0" conaffinity="0" />
<!-- Pen (Cylinder) attached to the tip of the distal link (left side) -->
<body name="pen" pos="0.19717 -0.0335 0">
<joint name="pen_joint" type="hinge" pos="0 0 0" axis="0 0 1" frictionloss="0.005" />
<geom type="cylinder" size="0.01 0.05" pos="0 0 0.03" rgba="0 0 1 0.8" contype="0" conaffinity="0"/>
<geom type="box" size="0.012 0.012 0.012" pos="0 0 0.07" rgba="0 0 1 0.8"/>
<site name="site_pen" pos="0 0 0"/>
</body>
</body>
</body>
<!-- Proximal link right side -->
<body name="l1_right" pos="0 -0.0335 0.05">
<joint name="j1_right" type="hinge" pos="0 0 0" axis="0 0 1" range="-1.57 0.785" frictionloss="0.005"/>
<geom type="capsule" fromto="0 0 0 0.2 0 0" size="0.01" density="800" rgba="0.5 0 0.5 0.8" />
<!-- Distal link right side -->
<body name="l2_right" pos="0.2 0 0">
<joint name="j2_right" type="hinge" pos="0 0 0" axis="0 0 1" frictionloss="0.005" />
<geom type="capsule" fromto="0 0 0 0.19717 0.0335 0" size="0.01" density="800" contype="0" conaffinity="0"/>
<!-- <site name="site_l2r_end" pos="0.2 0 0"/>-->
</body>
</body>
</worldbody>
<!-- Constraints -->
<equality>
<!-- Connect constraint to make a pin joint between the pen and the second arm -->
<connect body1="l2_right" body2="pen" anchor="0.19717 0.0335 0" />
</equality>
<!-- Actuation -->
<actuator>
<position name="motor_pos_left" joint="j1_left" kp="2" kv="0.08" ctrlrange="-0.785 1.57"/>
<position name="motor_pos_right" joint="j1_right" kp="2" kv="0.08" ctrlrange="-1.57 0.785"/>
<!-- <motor name="motor_torque_left" joint="j1_left" ctrlrange="-0.1 0.1" />-->
<!-- <motor name="motor_torque_right" joint="j1_right" ctrlrange="-0.1 0.1" />-->
</actuator>
</mujoco> |
Beta Was this translation helpful? Give feedback.
-
Hey, thanks for the detailed response! I’ll give this a try and let you know how it goes. The main issue I was facing is that the soft constraint tends to break under stress. I was originally using a weld constraint, but hadn’t tried the approach you suggested here. I’ll implement it and get back to you with the results. |
Beta Was this translation helpful? Give feedback.
-
Hi again, it's working now. Thanks a lot! I additionally used the solimp and solref tags as in the documentation to make the constraint stronger. Thanks again |
Beta Was this translation helpful? Give feedback.
Uh oh!
There was an error while loading. Please reload this page.
-
Intro
Hi!
I am an undergraduate student at the Indian Institute of Technology Roorkee, currently working with MuJoCo for research on quadrupeds. My project involves a custom quadruped where each leg is a 5-bar linkage.
My setup
Mujoco, python API, windows 11
My question
I’m facing difficulties implementing the joint constraints because the dependent joint angles follow nonlinear kinematic relationships that can’t be expressed as simple polynomials. Currently, I manually update the dependent joint angles in Python by setting qpos each simulation step. However, this approach leads to unrealistic contact forces with the ground and causes the robot to behave erratically, often “flying” off the ground.
I have also tried using weld constraints in the XML to enforce these joints, but they break during simulation.
Could you please help me with this?
Thanks so much for your help!

Minimal model and/or code that explain my question
No response
Confirmations
Beta Was this translation helpful? Give feedback.
All reactions