google-deepmind/mujoco_menagerie

Setting qpos does not take it to the same configuration

mochan-b opened this issue · 1 comments

Which model is the issue affecting?

I have tested this with both UR5e and UR10e.

What is the issue?

I set certain control values from the right panel and then save the qpos values.

When I set the same qpos value in ctrl, the robot pose it off by a little bit from that value (about 0.01m in z which is about 10mms).
This is from one of pose of one of the bodies in the UR robot.

Also, the same if I set the same value for data.qpos and data.ctrl.

Below is an example.

import mujoco.viewer


def get_body_pos(body_name):
    body_id = model.body(body_name).id
    body_pos = data.xpos[body_id]
    body_qpos = data.xquat[body_id]
    return body_pos, body_qpos


if __name__ == '__main__':
    model_name = 'mujoco_menagerie/universal_robots_ur5e/scene.xml'

    model = mujoco.MjModel.from_xml_path(model_name)
    data = mujoco.MjData(model)


    def key_callback(keycode):
        if keycode == 32:
            print(data.qpos)
            print(get_body_pos('wrist_3_link'))
        if keycode == 257:
            data.ctrl = [-4.83791, -1.64282974, -1.61030469, -1.32219651, 0.87980056, -2.01056]


    with mujoco.viewer.launch_passive(model, data, key_callback=key_callback) as viewer:
        # viewer.cam.lookat[:] = [-0.1094871, 0.6, 0.0579871]
        while viewer.is_running():
            mujoco.mj_step(model, data)
            viewer.sync()

So, I run the above script

  • Move the robot around to a configuration using the right panel
  • Press space bar to output the qpos and body position of wrist_3_link
  • I modify the code to put the previous qpos in the data.ctrl part
  • I press enter to move the body to data.ctrl value
  • I output the qpos and pose of the wrist_3_link

These are the values for one of the samples.

First line is original. Second is from setting the original qpos into the model.

QPos

q1 q2 q3 q4 q5 q6
-4.83791 -1.64283 -1.6103 -1.3222 0.879801 -2.01056
-4.83790995 -1.65224 -1.61818 -1.32497 0.879982 -2.01056
-5E-08 0.009413 0.00787 0.002769 -0.00018 -1E-08

Body position

x y z
0.49835338 -0.19795 0.556927
0.50175702 -0.19838 0.547905
-0.00340364 0.000429 0.009022

q2 seems to control the height and it makes sense that the error there causes the z to also have an error.

I am using dm_control.suite.base which uses only ctrl so the example is to show that.

Any insight into why this happens and what I can adjust in the model to fix it? I did try to play around with control parameters but it doesn't seem to work for everything from here

<general biastype="affine" ctrlrange="-6.2831 6.2831" gainprm="5000" biasprm="0 -5000 -500"/>

When I did the same with google robot test, the errors are 2e-8.

Actuators are not magic. They apply forces (which "fight" with other forces). The joint will never fully reach the target, though you can make the error as small as you like by increasing gains.