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

Actuator inertia #78

Open
nielsvd opened this issue Feb 11, 2016 · 6 comments
Open

Actuator inertia #78

nielsvd opened this issue Feb 11, 2016 · 6 comments

Comments

@nielsvd
Copy link

nielsvd commented Feb 11, 2016

Actuators used in industrial robotic arms typically have a reasonably low inertia, which can be included in the link inertia. However, the actuator inertia has another important effect on the rigid body dynamics; namely, due to the gear ratio between the motor and the joint, the actuator inertia significantly contributes to the required torque to achieve a certain requested motion.

At the moment it seems that the URDF specification does not support the specification of such contribution of motor inertia. I think it could be well-placed in the transmission tag.

Some relevant questions for the discussion:

  • Am I missing out on something (actuator inertia is supported)?
  • If not, is it in accordance to the philosophy behind URDF to include actuator inertia in the specification?
  • If so, do you agree it should be place in the transmission element?

Thanks in advance for your input.

@jacquelinekay
Copy link
Contributor

Correct, neither the transmission element nor the actuator element have inertia in URDF.

If we were to introduce actuator inertia, it would probably be as a sub-element of the actuator element, which is a sub-element of transmission.

I'm not a mechanical engineer, so can you provide a specific example, perhaps a formula for a motor model, where actuator inertia is needed and cannot be faked by some combinator of the joint dynamics and limit sub-elements?

@nielsvd
Copy link
Author

nielsvd commented Mar 2, 2016

Sorry for my late reply. Please find an example below (it's included as an image to display the maths nicely). To my knowledge the actuator inertia in the example below cannot be faked using existing elements in URDF.

two-link svg

@scpeters
Copy link
Contributor

scpeters commented Mar 2, 2016

This is excellent documentation! Thanks for this example. Here's my comments:

  • I assume that v_k is measured at the link center-of-mass.
  • As you suggest in the issue description, I think the transmission tag would be a good place for the actuator inertia.
  • Is there any case when the actuator inertia would not be a scalar, assuming it acts along a single joint axis?

@nielsvd
Copy link
Author

nielsvd commented Mar 3, 2016

In response to the comments by @scpeters:

  • Yes v_k is measured in the link center-of-mass, an important note I forgot to state in the example.
  • I am not aware of a case where a scalar-valued inertia doesn't suffice, indeed assuming the actuator acts along a single joint axis.

@neemoh
Copy link

neemoh commented Apr 14, 2020

Any update on this? I am surprised that motor inertia is not included in URDF. It is not something one can ignore when dealing with dynamics. Just to give you an example, the motor inertias (considering the gear ratio) of the first 2 joints of a 5kg payload robot can contribute 30-40% to the diagonals of the mass matrix.

@emekBaris
Copy link

emekBaris commented Apr 2, 2021

Is there any update? I tried to use the mimic tag of the Joint class to model this, but it only affects the kinematics but not the dynamics.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

5 participants