google-deepmind / mujoco

Multi-Joint dynamics with Contact. A general purpose physics simulator.
https://mujoco.org
Apache License 2.0
7.47k stars 734 forks source link

Simulating tension only cables with variable lengths #1704

Open Mnoritsugu opened 3 weeks ago

Mnoritsugu commented 3 weeks ago

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.

<mujoco model="cable">
    <asset>
        <texture type="skybox" builtin="gradient" rgb1="1 1 1" rgb2=".6 .8 1" width="256" height="256"/>
        <texture name="texplane" type="2d" builtin="checker" rgb1=".25 .25 .25" rgb2=".3 .3 .3" width="512" height="512" mark="cross" markrgb=".8 .8 .8"/>
        <material name="matplane" reflectance="0.3" texture="texplane" texrepeat="1 1" texuniform="true"/>
    </asset>

    <worldbody>
        <light pos="0 0 1"/>
        <geom name="floor" pos="0 0 -0.5" size="0 0 1" type="plane" material="matplane"/>

        <body name="base" pos="0 0 0">
            <geom type="box" size="0.03 0.03 0.03" density="100" rgba=".2 .5 .2 .5"/>
            <site name="cable_begin" pos="0 0 -0.03" size="0.01" rgba="1 0 0 1"/>
        </body>

        <body name="weight" pos="0 0 -0.3">
            <joint type="free"/>
            <geom type="cylinder" size=".05 .05" density="100"  rgba=".5 .2 .2 .5"/>
            <site name="cable_end" pos="0 0 0.05" size="0.01" rgba="1 0 0 1"/>
        </body>
    </worldbody>

    <tendon>
        <spatial name="tendon_cable" limited="false" damping="10">
            <site site="cable_begin"/>
            <site site="cable_end"/>
        </spatial>
    </tendon>

    <sensor>
        <tendonpos tendon="tendon_cable"/>
    </sensor>

    <actuator>
        <motor tendon="tendon_cable"/>
    </actuator>
</mujoco
import mujoco
import mujoco_viewer
import keyboard

def main():
    xml_path = "./model/xml/simple_winch2.xml"
    model = mujoco.MjModel.from_xml_path(xml_path)
    data = mujoco.MjData(model)
    viewer = mujoco_viewer.MujocoViewer(model, data)

    mujoco.mj_resetDataKeyframe(model, data, 0)

    natural_length = 0.22
    k_cable = 200
    time_step = 0.002
    cable_vel = 0.04

    while True:
        mujoco.mj_step(model, data)
        viewer.render()

        current_cable_length = data.sensordata[0]
        natural_length = control(natural_length, cable_vel, time_step)

        if current_cable_length > natural_length:
            data.ctrl[0] = -(current_cable_length - natural_length) * k_cable
        else:
            data.ctrl[0] = 0

        print(f"Naturallength: {natural_length:.4f} Current length: {current_cable_length:.4f}")

    viewer.close()

def control(natural_length, cable_vel, time_step):
    if keyboard.is_pressed('up'):
        print("Winch up")
        natural_length -= cable_vel * time_step
    elif keyboard.is_pressed('down'):
        print("Winch down")
        natural_length += cable_vel * time_step
    else:
        print("All actuator stop.", end='\r')

    return natural_length

if __name__ == "__main__":
    main()

Is there any other better method? Thank you in advance.

Balint-H commented 7 hours 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>