Moment of inertia calculation
Feature summary
A guide on how to use the ur_desciprtion physical_parameters.yaml to calculate the inertia of specific arm model. This can help cross-checking the effort data published on the /joint_states topic.
Right now, I use effort from topic /joint_states directly to calculate the workdone for the motion or the trajectory planned. However, as I am not so familiar it, I am not sure how this effort is calculated and packed into the msg. Thus, I would like to calculate the workdone using torque which is calculated from inertia * angular acceleration which is the dv/dt. I know this might have a slight difference for the calculated result.
I am using ur5e now and here is the parameter I can find:
inertia_parameters:
base_mass: 4.0 # This mass might be incorrect
shoulder_mass: 3.7000
upper_arm_mass: 8.3930
upper_arm_inertia_offset: 0.138 # measured from model
forearm_mass: 2.2750
wrist_1_mass: 1.2190
wrist_2_mass: 1.2190
wrist_3_mass: 0.1879
shoulder_radius: 0.060 # manually measured
upper_arm_radius: 0.054 # manually measured
elbow_radius: 0.060 # manually measured
forearm_radius: 0.040 # manually measured
wrist_radius: 0.045 # manually measured
links:
base:
radius: 0.06
length: 0.05
shoulder:
radius: 0.06
length: 0.15
upperarm:
radius: 0.06
length: 0.425
forearm:
radius: 0.06
length: 0.3922
wrist_1:
radius: 0.06
length: 0.12
wrist_2:
radius: 0.06
length: 0.12
wrist_3:
radius: 0.0375
length: 0.0458
center_of_mass:
shoulder_cog:
x: 0.0
y: 0.00193
z: -0.02561
upper_arm_cog:
x: 0.0
y: -0.024201
z: 0.2125
forearm_cog:
x: 0.0
y: 0.0265
z: 0.11993
wrist_1_cog:
x: 0.0
y: 0.110949
z: 0.01634
wrist_2_cog:
x: 0.0
y: 0.0018
z: 0.11099
wrist_3_cog:
x: 0.0
y: 0.001159
z: 0.0
Questions:
- What is
upper_armandforearm? And why theelbowis not being called? - What geometry should be considered when calculating the inertia? inertia wiki Should I use a hollow cylinder or a solid cylinder?
- The value is mismatch with the official DH table here
Related issues
N/A
Tasks
To complete this issue involves
- [ ] Implement the feature
- [ ] Make documentation
- [ ] Make Unit test
- [ ] Make example
- [ ] Test on real hardware
Great thanks for any ideas!
Thank you for your interest in this topic. I'm afraid, I cannot give you a full answer to everything, but to address some of your questions:
- What is upper_arm and forearm? And why the elbow is not being called?
Inertias are calculated for the links, not the joints. The elbow isn 't a link in the kinematic chain. Upper arm and forearm are the two main tubes respectively. If you look at the model in RViz, you can easily switch the individual links on and off.
- What geometry should be considered when calculating the inertia? inertia wiki Should I use a hollow cylinder or a solid cylinder?
- The value is mismatch with the official DH table here
I'll add https://github.com/ros-industrial/universal_robot/pull/504 as a comment to both questions. Inertia calculation is a bit more complicated than just the bodies, as motor inertia has to be taken into account, as well. We haven't had a deeper look into this, so far, so any help on this is highly welcome.
First of all, thanks for your answer!
Actually, I am conducting a study (master course) on the energy consumption of a planned trajectory. I am using UR5e with ursim to conduct the research. I found out there is a topic called /joint_states which provides the effort of each joint? or link.
Would you mind guiding me on which files/nodes pack those effect data and publish it to this topic? I would like reverse engineering to find out how it has been calculated.
The reason why I would like to re-calculate the moment of inertia is to double verify whether the published effort is trustable/close-to-accurate or not.
The effort readings are the actual currents on the joints and are packed here.