Unstable model without damping

Discussion in 'Modeling' started by Roberto, Jan 6, 2019.

  1. Hello,
    I am wondering if joint damping, friction or any other energy consuming force is strictly required for a model to be stable? I have been using the following model:

    <mujoco model="sawyer">
    <compiler angle="radian" />
    <size njmax="500" nconmax="100" />
    <asset>
    <mesh name="pedestal" file="pedestal.obj" />
    <mesh name="base" file="base.obj" />
    <mesh name="l0" file="l0.obj" />
    <mesh name="head" file="head.obj" />
    <mesh name="l1" file="l1.obj" />
    <mesh name="l2" file="l2.obj" />
    <mesh name="l3" file="l3.obj" />
    <mesh name="l4" file="l4.obj" />
    <mesh name="l5" file="l5.obj" />
    <mesh name="l6" file="l6.obj" />
    </asset>
    <worldbody>
    <body name="base" pos="0 0 0">
    <inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/>
    <body name="controller_box" pos="0 0 0">
    <inertial diaginertia="1.71363 1.27988 0.809981" mass="46.64" pos="-0.325 0 -0.38"/>
    <geom pos="-0.325 0 -0.38" size="0.11 0.2 0.265" type="box" name="controller_box_col"/>
    </body>
    <body name="pedestal_feet" pos="0 0 0">
    <inertial diaginertia="8.16095 9.59375 15.0785" mass="167.09" pos="-0.1225 0 -0.758"/>
    <geom pos="-0.1225 0 -0.758" size="0.385 0.35 0.155" type="box" name="pedestal_feet_col"/>
    </body>
    <body name="torso" pos="0 0 0">
    <inertial diaginertia="1e-08 1e-08 1e-08" mass="0.0001" pos="0 0 0"/>
    <geom conaffinity="0" contype="0" group="1" rgba="0.2 0.2 0.2 1" size="0.05 0.05 0.05" type="box" name="torso_col"/>
    </body>
    <body name="pedestal" pos="0 0 0">
    <inertial diaginertia="6.0869 5.81635 4.20915" mass="60.864" pos="0 0 0" quat="0.659267 -0.259505 -0.260945 0.655692"/>
    <geom conaffinity="0" contype="0" group="1" mesh="pedestal" pos="0.26 0.345 -0.91488" quat="0.5 0.5 -0.5 -0.5" rgba="0.2 0.2 0.2 1" type="mesh" name="pedestal_col1"/>
    <geom pos="-0.02 0 -0.29" rgba="0.2 0.2 0.2 1" size="0.18 0.31" type="cylinder" name="pedestal_col2"/>
    </body>
    <body name="right_arm_base_link" pos="0 0 0">
    <inertial pos="-0.0006241 -2.8025e-05 0.065404" quat="-0.209285 0.674441 0.227335 0.670558" mass="2.0687" diaginertia="0.00740351 0.00681776 0.00672942" />
    <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="base" />
    <body name="right_l0" pos="0 0 0.08">
    <inertial pos="0.024366 0.010969 0.14363" quat="0.894823 0.00899958 -0.170275 0.412573" mass="5.3213" diaginertia="0.0651588 0.0510944 0.0186218" />
    <joint name="right_j0" pos="0 0 0" axis="0 0 1" limited="true" range="-3.0503 3.0503" />
    <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="l0" />
    <body name="head" pos="0 0 0.2965">
    <inertial pos="0.0053207 -2.6549e-05 0.1021" quat="0.999993 7.08405e-05 -0.00359857 -0.000626247" mass="1.5795" diaginertia="0.0118334 0.00827089 0.00496574" />
    <!--<geom quat="0.707388 0.706825 0 0" type="mesh" contype="0" conaffinity="0" group="1" mesh="head" />-->
    </body>
    <body name="right_l1" pos="0.081 0.05 0.237" quat="0.5 -0.5 0.5 0.5">
    <inertial pos="-0.0030849 -0.026811 0.092521" quat="0.424888 0.891987 0.132364 -0.0794296" mass="4.505" diaginertia="0.0224339 0.0221624 0.0097097" />
    <joint name="right_j1" pos="0 0 0" axis="0 0 1" limited="true" range="-3.8095 2.2736" />
    <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="l1" />
    <body name="right_l2" pos="0 -0.14 0.1325" quat="0.707107 0.707107 0 0">
    <inertial pos="-0.00016044 -0.014967 0.13582" quat="0.707831 -0.0524761 0.0516007 0.702537" mass="1.745" diaginertia="0.0257928 0.025506 0.00292515" />
    <joint name="right_j2" pos="0 0 0" axis="0 0 1" limited="true" range="-3.0426 3.0426" />
    <geom quat="0.707388 0.706825 0 0" type="mesh" contype="0" conaffinity="0" group="1" mesh="l2" />
    <body name="right_l3" pos="0 -0.042 0.26" quat="0.707107 -0.707107 0 0">
    <inertial pos="-0.0048135 -0.0281 -0.084154" quat="0.902999 0.385391 -0.0880901 0.168247" mass="2.5097" diaginertia="0.0102404 0.0096997 0.00369622" />
    <joint name="right_j3" pos="0 0 0" axis="0 0 1" limited="true" range="-3.0439 3.0439" />
    <geom quat="0.707388 0.706825 0 0" type="mesh" contype="0" conaffinity="0" group="1" mesh="l3" />
    <body name="right_l4" pos="0 -0.125 -0.1265" quat="0.707107 0.707107 0 0">
    <inertial pos="-0.0018844 0.0069001 0.1341" quat="0.803612 0.031257 -0.0298334 0.593582" mass="1.1136" diaginertia="0.0136549 0.0135493 0.00127353" />
    <joint name="right_j4" pos="0 0 0" axis="0 0 1" limited="true" range="-2.9761 2.9761" />
    <geom quat="0.707388 0.706825 0 0" type="mesh" contype="0" conaffinity="0" group="1" mesh="l4" />
    <body name="right_l5" pos="0 0.031 0.275" quat="0.707107 -0.707107 0 0">
    <inertial pos="0.0061133 -0.023697 0.076416" quat="0.404076 0.9135 0.0473125 0.00158335" mass="1.5625" diaginertia="0.00474131 0.00422857 0.00190672" />
    <joint name="right_j5" pos="0 0 0" axis="0 0 1" limited="true" range="-2.9761 2.9761" />
    <geom quat="0.707388 0.706825 0 0" type="mesh" contype="0" conaffinity="0" group="1" mesh="l5" />
    <body name="right_l6" pos="0 -0.11 0.1053" quat="0.0616248 0.06163 -0.704416 0.704416">
    <inertial pos="-8.0726e-06 0.0085838 -0.0049566" quat="0.479044 0.515636 -0.513069 0.491322" mass="0.3292" diaginertia="0.000360258 0.000311068 0.000214974" />
    <joint name="right_j6" pos="0 0 0" axis="0 0 1" limited="true" range="-4.7124 4.7124" />
    <geom type="mesh" contype="0" conaffinity="0" group="1" mesh="l6" />
    <body name="right_hand" pos="0 0 0.0245" quat="0.707105 0 0 0.707108">
    <!-- To add gripper -->
    </body>
    </body>
    </body>
    </body>
    </body>
    </body>
    </body>
    </body>
    </body>
    </body>
    </worldbody>
    </mujoco>
    This model is unstable when I command a very small qfrc_applied (0.0001 in one joint).

    However, the same model is stable if I add either a default damping with
    <default>
    <joint limited='true' damping="1" />
    </default>​
    or if I add a velocity actuators adding
    <actuator>
    <velocity ctrllimited="true" ctrlrange="-1.74 1.74" joint="right_j0" kv="8.0" name="vel_right_j0"/>
    <velocity ctrllimited="true" ctrlrange="-1.328 1.328" joint="right_j1" kv="7.0" name="vel_right_j1"/>
    <velocity ctrllimited="true" ctrlrange="-1.957 1.957" joint="right_j2" kv="6.0" name="vel_right_j2"/>
    <velocity ctrllimited="true" ctrlrange="-1.957 1.957" joint="right_j3" kv="4.0" name="vel_right_j3"/>
    <velocity ctrllimited="true" ctrlrange="-3.485 3.485" joint="right_j4" kv="2.0" name="vel_right_j4"/>
    <velocity ctrllimited="true" ctrlrange="-3.485 3.485" joint="right_j5" kv="0.5" name="vel_right_j5"/>
    <velocity ctrllimited="true" ctrlrange="-4.545 4.545" joint="right_j6" kv="0.1" name="vel_right_j6"/>
    </actuator>
    Is that behavior to be expected? Shouldn't the inertia/mass of the links be sufficient to stabilize the system for small torques?

    Thank you so much for your help!

    --Roberto