franka_sim icon indicating copy to clipboard operation
franka_sim copied to clipboard

franka_sim panda0_link7 (wrist joint) have wrong rotation values compared to official urdf

Open Harimus opened this issue 1 year ago • 0 comments

While collecting some data from the real robot using polymetis (backbone for franka panda sim2real on robohive), and to double-check if it worked with the sim, I noticed some oddities. When playing back the collected data in the sim, the wrist was constantly off by about 45 degrees.

After checking around in the code base, I noticed that here:

https://github.com/vikashplus/franka_sim/blob/82aaf3bebfa29e00133a6eebc7684e793c668fc1/assets/chain0.xml#L45

The euler='1.57 0 0.7854' is not the same as the Franka official URDF, nor the one used in Polymetis.

The Franka official URDF, available in franka_ros package here

https://github.com/frankaemika/franka_ros/blob/c11f000c2737acc22ed8dfeff40555b2644a4294/franka_description/robots/common/franka_arm.xacro#L123

have the value rpy="${pi/2} 0 0" which corresponds to quaternion(wxyz) 0.7071068, 0.7071068, 0, 0. This is also the value used in the mujoco config file in Polymetis

https://github.com/facebookresearch/fairo/blob/0a01a7fa7a7c65b2f9a3aebf5e79040940daf9d2/polymetis/polymetis/data/franka_panda/panda_arm.mjcf#L41

and the urdf file in the same folder

https://github.com/facebookresearch/fairo/blob/0a01a7fa7a7c65b2f9a3aebf5e79040940daf9d2/polymetis/polymetis/data/franka_panda/panda_arm.urdf#L211

In Euler angle, this official rotation would correspond to euler='1.57 0 0'. So I was wondering why the additional 0.7854 was added. In the file, the correct quaternion values seems to be added as a comment.

So I was wondering if there's any reason for this custom rotational offshoot that I'm just not aware of, or can I throw a PR for a quick fix on this? (This might however cause some incompatibilities with existing dataset if there's something already collected in the sim, since image and joint position correspondence will be off by that amount)

Edit: It seems like joint 6 is also diverging from the original: https://github.com/vikashplus/franka_sim/blob/82aaf3bebfa29e00133a6eebc7684e793c668fc1/assets/chain0.xml#L38 (franka ros have rpy="${pi/2} 0 0" https://github.com/frankaemika/franka_ros/blob/c11f000c2737acc22ed8dfeff40555b2644a4294/franka_description/robots/common/franka_arm.xacro#L107 ) And the range of the joint_limits is set as range="-1.6573 2.1127" when the original is -0.0175 3.7525

Harimus avatar Apr 11 '24 07:04 Harimus