Open Mnoritsugu opened 3 weeks ago
Hello, as reference, docs for tendons: https://mujoco.readthedocs.io/en/latest/XMLreference.html#tendon-spatial Also relevant is position actuators: https://mujoco.readthedocs.io/en/latest/XMLreference.html#tendon-spatial
One way to achieve this could be setting a dead-band in springlength
that you change based on the control. If you don't want to be so elastic, you can instead set the range
of the tendon instead.
def ctrl_callback(model, data):
"""
:type model: mujoco.MjModel
:type data: mujoco.MjData
"""
model.tendon_range[0, 1] = (np.sin(data.time * 1)+1)/2
model.tendon_limited[0] = True
Another simpler way would be to use a position actuator, and set the forcerange
to have 0 as its upper limit (and some large negative value as the lower). That will achieve a tension-only actuation the same way as your example without additional conditions, but it will be quite elastic/bouncy (as I'm not sure how to set up in MJCF damping to only trigger beyond a certain length. It can of course be done in the control loop).
<mujoco>
<visual>
<map force="0.1" zfar="30"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global offwidth="2560" offheight="1440" elevation="-20" azimuth="120"/>
</visual>
<asset>
<texture type="skybox" builtin="gradient" rgb1=".3 .5 .7" rgb2="0 0 0" width="32" 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>
<geom name="floor" size="0 0 .05" type="plane" material="grid" condim="3"/>
<light name="spotlight" mode="targetbodycom" target="b1" diffuse=".8 .8 .8" specular="0.3 0.3 0.3" pos="0 -6 4" cutoff="30"/>
<site name="s1" pos="0 0 1"/>
<body name="b1" pos="0 0 0.5">
<joint type="slide" axis="0 0 1"/>
<site name="s2" />
<geom type="sphere" size="0.05"/>
</body>
</worldbody>
<tendon >
<spatial name="t1" damping="1">
<site site="s1"/>
<site site="s2"/>
</spatial>
</tendon>
<actuator>
<position tendon="t1" kp="3000" forcerange="-100000 0" ctrlrange="0.5 1"/>
</actuator>
</mujoco>
Hi,
I'm an engineer and I'm trying to use MuJoCo to simulate cable suspenended robot like crane. I'm looking for some help with implementation of cable which applies pulling force and doesn't apply pushing force.
This thread is very close to what we want to do, but we want to change the cable length. Changing the length of a cable means that natural length of spring changes.
Here is the simple model and Python script which achieve our objective. Currently, I attached the sensor and actuator to the tendon which is implemented as a cable, and I apply pulling force based on the difference between current cable length and natural cable length.
Is there any other better method? Thank you in advance.