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

Inertia values in the Reachy URDF file #230

Open
danyalsaqib opened this issue Jul 6, 2023 · 1 comment
Open

Inertia values in the Reachy URDF file #230

danyalsaqib opened this issue Jul 6, 2023 · 1 comment
Labels
bug Something isn't working

Comments

@danyalsaqib
Copy link

Hi,

I have been working with Reachy's URDF file in conjunction with the Pinocchio library for torque estimation within the joints. However, when using Pinocchio's Recursive Newton-Euler Algorithm (RNEA) alongside Reachy's URDF model, I get incredibly high values for the torque - on the scale of 106. I was getting these values both when running the algorithm directly on the Reachy, and when I used the URDF file on my own machine. A small sample code for testing and the obtained output have been given below:

import pinocchio as pin
import numpy as np

model = pin.buildModelFromUrdf('reachy.urdf')
data = model.createData()

q = 	np.array([1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0])
qdot = 	np.array([2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0])
qddot = np.array([5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0])

tau = pin.rnea(model,data,q,qdot,qddot)
torques = np.transpose(tau.T)

print('tau: ', torques)
print ("torques shape = ", torques.shape)

------------------------------------------------------------------------------------------------------------

tau:  [-1.90936234e+06  1.48436960e+06  2.27592374e+06 -1.03214767e+06
  1.54283432e+06  8.84655651e+05 -2.26789326e+06 -2.67554168e-04
 -4.57972663e-03  1.48784404e-05 -8.05013070e-04  2.41186508e-06
 -2.41186508e-06 -1.46855700e-02 -4.10450400e-02  0.00000000e+00
 -3.98776500e-02  0.00000000e+00 -5.25914100e-02 -4.10450400e-02
 -1.47640500e-02]

torques shape =  (21,)

These extremely high values seemed quite unreasonable for the values of position, velocity, and acceleration provided. However, when digging further through the URDF files, I came across the 'reachy.URDF.xacro' file, which, when compared to the original URDF file, seems to have significantly different inertia values for the following links:

  • r_shoulder_x
  • l_shoulder_x
  • l_gripper_thumb

The original URDF file contains extremely high inertia values for these links, whereas the 'reachy.URDF.xacro' file seems to have much smaller values. The high inertia values are present in all of the other URDF files I have seen as well (including reachy_2023). However, when I replace these high inertia values with the ones I found in 'reachy.URDF.xacro', I get the following results with the modded URDF file:

import pinocchio as pin
import numpy as np

model = pin.buildModelFromUrdf('reachy_modded.urdf') # the urdf file with modified values for the 3 links
data = model.createData()

q = 	np.array([1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0])
qdot = 	np.array([2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0])
qddot = np.array([5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0])

tau = pin.rnea(model,data,q,qdot,qddot)
torques = np.transpose(tau.T)

print('tau: ', torques)
print ("torques shape = ", torques.shape)

------------------------------------------------------------------------------------------------------------

tau:  [ 1.72699519e+00  1.44701174e+00 -7.87977043e-01  2.26095090e-01
 -2.12862704e-02 -3.65070543e-02  9.62690374e-03 -2.67554168e-04
 -4.57972663e-03  1.48784404e-05 -8.05013070e-04  2.41186508e-06
 -2.41186508e-06 -1.46855700e-02 -4.10450400e-02  0.00000000e+00
 -3.98776500e-02  0.00000000e+00 -5.25914100e-02 -4.10450400e-02
 -1.47640500e-02]

torques shape =  (21,)

The torques I get from this modified URDF seem to be much more reasonable. I wanted to basically ask if these very high inertia values in the URDF files are correct, or if the values present in 'reachy.URDF.xacro' are the correct ones, because the latter ones seem to give much more reasonable results.

I'd like to also note here that I believe I am using Reachy 2021, and this discrepancy in inertia values was present on the files on our actual Reachy robot as well. Since the reachy_description GitHub repository has been archived, and the high inertia values seem to be present in reachy_2023 as well, I thought I'd open the issue here.

I would be highly grateful for any help in this matter. Thank you.

@pierre-rouanet
Copy link
Member

Thanks for letting us know!
The physical model of the arm almost did not change between the 2021 and 2023, so you can use the value from the reachy_description package.
I'll let the issue open so we update the URDF with the correct values!

@pierre-rouanet pierre-rouanet added the bug Something isn't working label Jul 12, 2023
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

2 participants