Mass / Inertia Matrix different to the expected value

Discussion in 'Simulation' started by Roberto, Dec 21, 2018.

  1. Hi,

    I'm having a problem to obtain the right inertia matrix in Mujoco. I tested with other simulator (SAI) using the same model (URDF instead of the MJCF, but one was generated from the other and contain same parameters) and the inertia matrix is very different, and the behavior is also different. I'm trying to decouple inertia effects in operational space and that does not work as expected in Mujoco while it does work as expected in the other simulator.

    I'm loading the model with the mjfc file attached and querying the inertia matrix at the joint configuration qpos = [0, -1.18, 0.00, 2.18, 0.00, 0.57, 3.3161]. There is a second free object in the environment. Thus, the size of qpos is 7 (joints of robot) + 7 (position and orientation of object) = 14 and the size of qvel is 7+6 = 13. The indices of the dofs of the robot are in a vector self._ref_joint_vel_indexes

    I use this code with the mujoco-py python wrapper to get the full inertia matrix:

    mass_matrix = np.ndarray(shape=(len(self.sim.data.qvel)**2,),dtype=np.float64, order='C')
    mujoco_py.cymj._mj_fullM(self.sim.model, mass_matrix, self.sim.data.qM)
    mass_matrix = np.reshape(mass_matrix, (len(self.sim.data.qvel),len(self.sim.data.qvel)))
    mass_matrix = mass_matrix[self._ref_joint_vel_indexes,:][:,self._ref_joint_vel_indexes]

    In Mujoco, the resulting mass matrix from the previous code is the following:
    [[ 1.46820139e+00 -1.27564466e-01 7.51952798e-01 1.43553632e-01
    -2.44861687e-01 2.33200376e-02 -2.99059291e-01]
    [-1.27564466e-01 1.34566188e+00 1.87242150e-01 5.59138568e-01
    -6.63851858e-02 3.14168544e-01 3.68203225e-05]
    [ 7.51952798e-01 1.87242150e-01 7.60309657e-01 -6.56085136e-02
    -1.27982459e-01 -7.45641903e-03 -2.76633279e-01]
    [ 1.43553632e-01 5.59138568e-01 -6.56085136e-02 9.29645338e-01
    -1.35436226e-01 3.79017751e-01 2.17265661e-04]
    [-2.44861687e-01 -6.63851858e-02 -1.27982459e-01 -1.35436226e-01
    3.47068706e-01 -1.69016581e-02 2.52998667e-01]
    [ 2.33200376e-02 3.14168544e-01 -7.45641903e-03 3.79017751e-01
    -1.69016581e-02 3.24327827e-01 5.29076303e-05]
    [-2.99059291e-01 3.68203225e-05 -2.76633279e-01 2.17265661e-04
    2.52998667e-01 5.29076303e-05 3.00384056e-01]]

    In the other simulator, the result is:
    1.03685 -0.139152 0.37437 0.099839 -0.0077165 0.0088435 -0.000809897
    -0.139152 0.955719 0.186679 0.173346 -0.0421297 0.0020806 -0.000212136
    0.37437 0.186679 0.369744 -0.0571182 0.0204666 -0.00414665 -0.000271658
    0.099839 0.173346 -0.0571182 0.452004 -0.093221 0.030013 -0.00125689
    -0.0077165 -0.0421297 0.0204666 -0.093221 0.0318539 -0.00607289 0.000647616
    0.0088435 0.0020806 -0.00414665 0.030013 -0.00607289 0.00795993 -0.000305284
    -0.000809897 -0.000212136 -0.000271658 -0.00125689 0.000647616 -0.000305284 0.000384016

    The values are quite different, although not completely. Strangely, in Mujoco the diagonal element for the last joint is very high (around 0.3) compared to the result of the second simulator (0.0003). Physically I expect that value to be small since the last link is just the mounting plate for the robot hand, no robot hand attached.

    I'm wondering if I am querying the mass matrix correctly and if there could be any other potential differences or things I am not considering. Or if the mass matrix has some other meaning/units in Mujoco.

    Did someone obtained the correct mass matrix? Or even better, did someone do dynamics decoupling in operational space?

    Thank you very much, any hint is appreciated.

    --roberto
     

    Attached Files: