How to correctly use slider-crank transmission for cylinders? #374
-
I have a XML Structure<body name="parent_1">
<geom name="parent_1_geom" type="mesh" mesh="parent_1_mesh" />
<body name="arm" >
<joint name="joint_arm" type="hinge" />
<geom name="arm_geom" type="mesh" mesh="arm_mesh" />
</body>
<body name="parent_2" >
<joint name="connecting_joint" type="hinge" />
<geom name="parent_2_geom" type="mesh" mesh="parent_2_mesh"/>
<body name="rod" >
<joint name="joint_rod" type="slide"/>
<geom name="rod_geom" type="mesh" mesh="rod_mesh" />
</body>
</body>
</body>
<equality>
<connect name="connect_1" body1="rod" body2="arm" anchor=" some_x some_y some_z" />
</equality>
<actuator>
<position name="position_actuator_rod" joint="joint_rod" kp="100" />
<position name="position_actuator_arm" joint="joint_arm" kp="100" />
</actuator> 1.Parent_1, 2.Parent_2, 3. Rod, 4. ArmI use the following to control the rod to move the arm, the equality seems to disappear: Equality/connect seems to disappearid = mujoco.mj_name2id(
model,
mujoco.mjtObj.mjOBJ_ACTUATOR,
"position_actuator_rod") # This joint is slide, inbetween body 2 and 3
data.ctrl[id] = some_changing_value mujoco_equality_ctrl_problem_1.1.mp4Equality/connect works the other wayid = mujoco.mj_name2id(
model,
mujoco.mjtObj.mjOBJ_ACTUATOR,
"position_actuator_arm") # This joint is revolute, inbetween body 4 and 1
data.ctrl[id] = some_changing_value mujoco_equality_ctrl_problem_1.2.mp4 |
Beta Was this translation helpful? Give feedback.
Replies: 8 comments 6 replies
-
I'll look more carefully soon at the details, but if you are trying to implement a slider-crank you should know that MuJuCo has a native slider-crank transmission type (search the docs, I'm currently AFK), equality constraints not required. |
Beta Was this translation helpful? Give feedback.
-
Having taken a look, I can't really reproduce what you are seeing so can't really diagnose. If you are still experiencing a strange issue, please attach a full loadable model as a zip file and I'll take a look. However as I said, if you have slider-cranks in your model you should use the build-in slider-crank transmission mechanism, as it adds no DoFs or equality constraints to your model and is significantly more efficient than your current approach (which is also valid, just less efficient). Here is a minimal model implementing a slider-crank. Note that it has exactly 1 DoF. Load it in <mujoco>
<worldbody>
<site name="slidersite" pos="0 -.1 0" zaxis="0 1 0" size=".012" rgba="1 0 0 1"/>
<body>
<joint damping=".1"/>
<geom type="capsule" size=".01" fromto="0 0 0 .2 0 0"/>
<site name="cranksite" pos=".1 0 0" size=".012" rgba="1 0 0 1"/>
</body>
</worldbody>
<actuator>
<position name="slider-crank" cranksite="cranksite" slidersite="slidersite" cranklength=".11"
ctrllimited="true" ctrlrange="-.1 .1" kp="30"/>
</actuator>
</mujoco> slider-crank transmissions are currently not well documented. Let us know if you end up using this and we might add better documentation. |
Beta Was this translation helpful? Give feedback.
-
I apologize for the inaccurate explanation on my part, I wanted to create this: |
Beta Was this translation helpful? Give feedback.
-
MuJoCo's mechanism supports both of these. Here is a model that shows how to make both forward and backward slider-cranks, and includes an example of a "broken" mechanism which cannot maintain the requested relationship at the initial state. educational slider-crank model<mujoco model="slider-crank">
<!-- these are the visual properties associated with the slider-crank mechanism: -->
<visual>
<scale slidercrank=".1"/>
<rgba slidercrank="0.5 0.4 0.8 1" crankbroken="0.0 0.6 0.2 1"/>
</visual>
<!-- defining some defaults for readability -->
<default>
<position ctrllimited="true" ctrlrange="-.1 .1" kp="30"/>
<default class="joint">
<geom type="cylinder" size=".006" fromto="0 0 0 0 0 .05" rgba=".9 .6 1 1"/>
</default>
<default class="slidersite">
<site type="cylinder" size=".01 .015" rgba="1 0 0 1" />
</default>
<default class="cranksite">
<site size=".012" rgba="0 0 1 1" />
</default>
</default>
<worldbody>
<light pos="0 0 1"/>
<geom type="plane" size=".5 .5 .01" pos="0 0 -.05"/>
<site name="slidersite" class="slidersite" pos="0 -.1 0" zaxis="1 .5 0"/>
<body>
<joint damping=".1"/>
<geom class="joint"/>
<geom type="capsule" size=".01" fromto="0 0 0 .2 0 0"/>
<site name="cranksite" class="cranksite" pos=".1 0 0"/>
<site name="cranksite2" class="cranksite" pos=".2 0 0"/>
<body pos=".15 0 0">
<joint damping=".1"/>
<geom class="joint"/>
<geom type="capsule" size=".01" fromto="0 -.15 0 0 0 0"/>
<site name="slidersite2" class="slidersite" pos=".02 -.1 0" euler="-90 30 0"/>
</body>
</body>
<site name="slidersite3" class="slidersite" pos="0 .1 0" zaxis="1 .2 0"/>
<body pos="0 .2 0">
<joint damping=".1"/>
<geom class="joint"/>
<geom type="capsule" size=".01" fromto="0 0 0 .15 0 0"/>
<site name="cranksite3" class="cranksite" pos=".1 0 0" size=".012"/>
</body>
</worldbody>
<actuator>
<!-- forward slider-crank: the slider site is attached to the parent -->
<position name="forward" cranksite="cranksite" slidersite="slidersite" cranklength=".08"/>
<!-- backward slider-crank: the slider site is attached to the child -->
<position name="backward" cranksite="cranksite2" slidersite="slidersite2" cranklength=".06"/>
<!-- The "broken-crank" actuator is "broken" in the initial state: the crank length is too
short to maintain the requested geometric relationship -->
<position name="broken" cranksite="cranksite3" slidersite="slidersite3" cranklength=".05"/>
</actuator>
</mujoco> Here is a riddle to check your understanding. The orientation of |
Beta Was this translation helpful? Give feedback.
-
Thank you for the second example(broken-crank), it cleared much confusion. Confused from trail from 1st example<mujoco>
<worldbody>
<body name="fixed_arm" pos="0 -.1 0">
<geom type="box" size=".01 .09 .01" rgba="1 0 0 .5" />
<body name="pink_capsule" pos="0 -.1 0" euler="90 153.5 0">
<joint axis="0 1 0" />
<geom type="capsule" size=".02 .03" pos="0 0 .1" rgba="1 0 1 .5" />
<site name="slidersite" pos="0 0 0" zaxis="0 0 1" size=".012" rgba="1 0 0 1" />
<body name="rod" pos="0 0 .15">
<joint name="slide_joint" type="slide" axis="0 0 1" />
<geom type="capsule" size=".015 .025" rgba="1 1 .1 1" />
</body>
</body>
<body pos="0 .1 0">
<joint name="main_pivot" damping=".1" range="-0.5 1.6" limited="true" />
<geom type="capsule" size=".01" fromto=".02 0 0 .2 0 0" />
<site name="cranksite" pos=".1 0 0" size=".012" rgba="1 0 0 1" />
<body name="connecting_box" pos=".1 0 0">
<joint />
<geom type="box" size=".01 .01 .01" />
</body>
</body>
</body>
</worldbody>
<actuator>
<position name="slider-crank" cranksite="cranksite" slidersite="slidersite" cranklength=".11" kp="200" />
<!-- ctrllimited="true" ctrlrange="-1 1" kp="30" -->
<motor name="force_act" joint="slide_joint" gear="1" ctrllimited="true" ctrlrange="-100 100" />
</actuator>
<equality>
<weld body1="connecting_box" body2="rod" />
</equality>
<contact>
<exclude body1="fixed_arm" body2="pink_capsule" />
</contact>
</mujoco> mujoco_slider_crank_cylinder.mp4But ended up having a Misalignment issue when the links were rotated(prehaps due to soft constraints?):mujoco_slider_crank_misalignment_problem.mp4Albeit, I did not fully understand the way the slider-crank is supposed to be used. Which part of the generated geom was the slider, and which part was the crank? Why does one of them switch from red to purple as I adjust the actuator value? Why/how is the force from this silder crank not working? etc The 2nd example of the slider-crank, i.e the educational slider-crank model and your question related to the From frame-orientations/zaxis:
This makes it easier to use
Solving for CrankIf I understand this correctly, mujoco solves and moves the geom for all possible radii of the cranks(black circles) to intersect to the Zaxis of of the slider(purple cylindrical part of the slider-crank) until the The 1st few seconds of the video below, it appears as if the joint between the green(unsolved) crank and the capsule geom does not change, only after the geom itself is rotated so as not to violate the specified
Video:Broken crank: @ timestep=1e-6mujoco_slider_crank_broken_priority.mp4So, Ideally for a robot,
|
Beta Was this translation helpful? Give feedback.
-
Can we lock joint at the |
Beta Was this translation helpful? Give feedback.
-
If it helps, here is the slider-crank visualisation code and here is the code computing the transmission (length + moment arm). Try to think of it in the opposite direction that the force is going. MuJoCo is trying to compute the function:
(The reason the function needs to be closed-form is that we care about its Jacobian (the "moment-arm matrix"), not just its value) |
Beta Was this translation helpful? Give feedback.
-
For future readers, playing with the time-step, Videomujoco_Is_weld_better_than_connect.mp4XML<mujoco model="slider-crank">
<option timestep="0.0001" gravity="0 0 -9.81" collision="predefined" />
<worldbody>
<light pos="0 0 1" />
<geom type="plane" size="3 3 .01" pos="0 0 -.2" />
<body name="b_root" pos="0 0 2" euler="0 90 0">
<geom name="g_root_1" type="box" fromto="0 0 0 1 0 0" size="0.05" rgba="0 1 .1 .5" mass="0.0001" />
<geom name="g_root_2" type="cylinder" fromto="1 0 -.1 1 0 .1" size="0.08" rgba="0 1 .1 1" mass="0.0001" />
<body name="b_arm" pos="1 0 0">
<joint name="hinge_joint_j1" type="hinge" />
<geom name="g_arm_1" type="cylinder" fromto="0 0 -.1 0 0 .1" size="0.08" rgba="1 0 .1 1" mass="0.0001" />
<geom name="g_arm_2" type="box" fromto="0 0 0 0 1 0" size="0.05" rgba="1 0 .1 .5" mass="0.0001" />
<geom name="g_arm_3" pos="0 1 0" type="sphere" size="0.03" rgba="1 0 .1 1" mass="1" />
</body>
<body name="b_cyl" pos=".2 0 0" euler="0 0 -45">
<joint name="j2" type="hinge" />
<geom name="g_cyl_1" type="cylinder" fromto="0 0 -.1 0 0 .1" size="0.03" rgba="1 0 .1 1" mass="0.0001" />
<geom name="g_cyl_2" type="cylinder" fromto="0 0 0 0 0.565685424949238 0" size="0.05" rgba="1 0 .1 .5" mass="0.0001" />
<body name="b_piston" pos="0 0.565685424949238 0">
<joint name="slide_joint_j3" type="slide" axis="0 1 0" />
<geom name="g_piston_1" type="cylinder" fromto="0 0.565685424949238 -.1 0 0.565685424949238 .1" size="0.03" rgba="1 0 .1 1" mass="0.0001" />
<geom name="g_piston_2" type="cylinder" fromto="0 0 0 0 0.565685424949238 0" size="0.02" rgba="1 0 .1 .5" mass="0.0001" />
<body name="weld_me" pos="0 0.565685424949238 0" euler="0 0 45">
<joint name="weld_j" />
<geom name="g_piston_weld_2" type="cylinder" fromto="0 0 -.1 0 0 .1" size="0.03" rgba="1 1 .1 1" mass="0.0001" />
</body>
</body>
</body>
</body>
<body name="b_root_1" pos="1 0 2" euler="0 90 0">
<geom name="g_root_1_1" type="box" fromto="0 0 0 1 0 0" size="0.05" rgba="0 .1 1 .5" mass="0.0001" />
<geom name="g_root_2_2" type="cylinder" fromto="1 0 -.1 1 0 .1" size="0.08" rgba="0 1 .1 1" mass="0.0001" />
<body name="b_arm_1" pos="1 0 0">
<joint name="hinge_joint_j1_1" type="hinge" />
<geom name="g_arm_1_1" type="cylinder" fromto="0 0 -.1 0 0 .1" size="0.08" rgba="1 0 .1 1" mass="0.0001" />
<geom name="g_arm_2_1" type="box" fromto="0 0 0 0 1 0" size="0.05" rgba="1 0 .1 .5" mass="0.0001" />
<geom name="g_arm_3_1" pos="0 1 0" type="sphere" size="0.03" rgba="1 0 .1 1" mass="1" />
</body>
<body name="b_cyl_1" pos=".2 0 0" euler="0 0 -45">
<joint name="j2_1" type="hinge" />
<geom name="g_cyl_1_1" type="cylinder" fromto="0 0 -.1 0 0 .1" size="0.03" rgba="1 0 .1 1" mass="0.0001" />
<geom name="g_cyl_2_1" type="cylinder" fromto="0 0 0 0 0.565685424949238 0" size="0.05" rgba="1 0 .1 .5" mass="0.0001" />
<body name="b_piston_1" pos="0 0.565685424949238 0">
<joint name="slide_joint_j3_1" type="slide" axis="0 1 0" />
<geom name="g_piston_1_1" type="cylinder" fromto="0 0.565685424949238 -.1 0 0.565685424949238 .1" size="0.03" rgba="1 0 .1 1" mass="0.0001" />
<geom name="g_piston_2_1" type="cylinder" fromto="0 0 0 0 0.565685424949238 0" size="0.02" rgba="1 0 .1 .5" mass="0.0001" />
<body name="weld_me_1" pos="0 0.565685424949238 0" euler="0 0 45">
<joint name="weld_j_1" />
<geom name="g_piston_weld_2_1" type="cylinder" fromto="0 0 -.1 0 0 .1" size="0.03" rgba="1 1 .1 1" mass="0.0001" />
</body>
</body>
</body>
</body>
</worldbody>
<equality>
<weld name="weld_1" active="true" body1="b_arm" body2="weld_me" relpose="0 0.8 0 1 0 0 0" solref="0.0002 1" />
<connect name="connect_1_1" active="true" body1="weld_me_1" body2="b_arm_1" anchor="0 0.565685424949238 0" />
</equality>
<actuator>
<!-- <position name="j1_act" joint="hinge_joint_j1" kp="1000" /> -->
<!-- <position name="j1_act_1" joint="hinge_joint_j1_1" kp="1000" /> -->
<position name="j3_act" joint="slide_joint_j3" kp="1000" />
<position name="j3_act_1" joint="slide_joint_j3_1" kp="10" />
</actuator>
<sensor>
<jointpos name="j1_sensor" joint="hinge_joint_j1" />
<jointpos name="j1_sensor_1" joint="hinge_joint_j1_1" />
</sensor>
</mujoco> |
Beta Was this translation helpful? Give feedback.
MuJoCo's mechanism supports both of these.
Did you actually load my example model in
simulate
and play with it?Here is a model that shows how to make both forward and backward slider-cranks, and includes an example of a "broken" mechanism which cannot maintain the requested relationship at the initial state.
educational slider-crank model