Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Equality constraint bounciness #278

Closed
rohit-kumar-j opened this issue May 16, 2022 · 3 comments
Closed

Equality constraint bounciness #278

rohit-kumar-j opened this issue May 16, 2022 · 3 comments

Comments

@rohit-kumar-j
Copy link

How to eliminate equality constraint's bounciness?

equality.constraint-.bouncing.problem.mp4
MJCF file
<mujoco>
    <compiler angle="degree" />
    <option gravity="0 0 0" timestep="0.002" />
    <asset>
        <material name="blue_" rgba="0 0 1 1" />
        <material name="green" rgba="0 1 0 1" />
        <material name="red__" rgba="1 0 0 1" />
        <material name="white" rgba="1 1 1 1" />
    </asset>
    <worldbody>
        <geom type="plane" size="10 10 0.1" pos="0 0 -3" rgba=".9 0 0 1" />
        <light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1" />
        <body name="link_1" pos="0 0 0">
            <geom type="cylinder" size=".2    2" pos="0 0 2" euler="0 0 0" material="red__" mass="0.8" />
            <geom type="cylinder" size=".25 .25" pos="0 0 4" euler="0 90 0" material="red__" mass="0.1" />
            <geom type="cylinder" size=".25 .25" pos="0 0 0" euler="0 90 0" material="red__" mass="0.1" />
            <body name="link_2" pos="0.5 0 0" euler="0 0 0">
                <joint name="hinge_1" type="hinge" pos="0 0 0" axis="1 0 0" /> <!--limited="true" range="-30 30" -->
                <geom type="cylinder" size=".2    2" pos="0 2 0" euler="90 0 0" material="blue_" mass="0.8" />
                <geom type="cylinder" size=".25 .25" pos="0 4 0" euler="0 90 0" material="blue_" mass="0.1" />
                <geom type="cylinder" size=".25 .25" pos="0 0 0" euler="0 90 0" material="blue_" mass="0.1" />
                <body name="link_3" pos="-0.5 4 0" euler="0 0 0">
                    <joint name="hinge_2" type="hinge" pos="0 0 0" axis="1 0 0" />
                    <geom type="cylinder" size=".2    2" pos="0 0 2" euler="0 0 0" material="green" mass="0.8" />
                    <geom type="cylinder" size=".25 .25" pos="0 0 0" euler="0 90 0" material="green" mass="0.1" />
                    <geom type="cylinder" size=".25 .25" pos="0 0 4" euler="0 90 0" material="green" mass="0.1" />
                    <body name="link_4" pos="0.5 0 4" euler="0 0 0">
                        <joint name="hinge_3" type="hinge" pos="0 0 0" axis="1 0 0" />
                        <geom type="cylinder" size=".2    2" pos="0 -2 0" euler="90 0 0" material="white" mass="0.8" />
                        <geom type="cylinder" size=".25 .25" pos="0 0 0" euler="0 90 0" material="white" mass="0.1" />
                        <geom type="cylinder" size=".25 .25" pos="0 -4 0" euler="0 90 0" material="white" mass="0.1" />
                    </body>
                </body>
            </body>
        </body>
    </worldbody>
    <equality>
        <connect name="kinematic_link" active="true" body1="link_1" body2="link_4" anchor="0 0 4" />
    </equality>
    <actuator>
        <motor name="hinge_1" joint="hinge_1" forcelimited="true" forcerange="-1000 1000" /> <!-- gear="1"  -->
        <position name="position_servo" joint="hinge_1" kp="100" />
        <velocity name="velocity_servo" joint="hinge_1" kv="100" />
    </actuator>
    <sensor>
        <jointpos name="pos_sensor_1" joint="hinge_1" />
        <jointpos name="pos_sensor_2" joint="hinge_2" />
        <jointpos name="pos_sensor_3" joint="hinge_3" />
    </sensor>
</mujoco>
@yuvaltassa
Copy link
Collaborator

Hi,

Thanks for the screen capture!
Equality constraints have solimp and solref parameters, this section has more details.

Short short version: reduce solref[0]. It can only be reduced as far as 2*timestep (below which is is clamped internally), so if that's not stiff enough for you, you might need to reduce your timestep.

@rohit-kumar-j
Copy link
Author

rohit-kumar-j commented May 17, 2022

Thanks @yuvaltassa the bounciness is gone, but there is contact penetration between the links. The simulation seems much slower, perhaps due to the lower timestep. If the collision velocity is high, seems like the contact is not detected easily. Perhaps, the easiest method is by defining joint max and min range.

<mujoco>
    <option gravity="0 0 0" timestep="0.0001" />
    <equality>
        ... solref="0.0002 1"
    </equality>
</mujoco>
contact-penetration-mujoco.mp4

@yuvaltassa
Copy link
Collaborator

yuvaltassa commented May 17, 2022

Well, the contacts of course also have solver parameters. Try reducing solref for your geoms, perhaps with a default clause:

<default>
  <geom solref="X 1"/>
</default>

I am guessing that the slowness indeed comes from lowering the timestep too aggressively. Once you've increased the contact stiffness as above and are happy with the behaviour, you should try increasing the timestep back again.

As a side note, we are well aware that MuJoCo's default solver parameters are too soft for most use cases. However changing default values is not something that can be done without breaking existing models. We hope to introduce some form of versioning in the near future that would allow the user to achieve this result with less tinkering.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants