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

Modify stickbot urdf #16

Merged
merged 2 commits into from
Dec 10, 2021

Conversation

CarlottaSartore
Copy link
Contributor

@CarlottaSartore CarlottaSartore commented Dec 9, 2021

This PR addresses #15 and changes the links masses as per robotology/icub-models#94, now the robot weight is equal to

idyntree-model-info -m model.urdf --total-mass
[WARNING] SensorElement :: setAttributes : iDynTree does not support sensor of type depth
[WARNING] SensorElement :: setAttributes : iDynTree does not support sensor of type camera
The total mass of model is 52.0102 Kg.

Note that there was the need of recomputing the inertias since the mass changed, I used directly the script inside ergocub gazebo simulator to perform the computation for the changes.
⚠️ the mass of the robot is not exactly equal to the one of icub3 but there are new links (such as the lidar) that increase the mass of the robot.

Since I was already there I have:

C.C. @AlexAntn @GrmanRodriguez @Nicogene @lrapetti @DanielePucci

<axis xyz="0 0 1.0"/>
<origin xyz="0.05305 0.0 0.08205" rpy="1.5708 3.1415 0.0"/>
<axis xyz="0. 0. 1."/>
<origin xyz="0.05305 0.0 0.08205" rpy="-1.5707926535897934 9.265358979305728e-05 -3.141592653589793"/>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why was the orientation of this joint changed?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks @GrmanRodriguez ! It should not change, I think this was changed by the script. I applied a modification of all the links with a length multiplier of 1 (i.e. no change).
I will investigate why that orientation (and the other origins ) changed! It could be that some parameters of the joint modifier could be wrong (seems to be a flip of direction maybe ? )

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fix it in commit 32f38dd

Copy link
Member

@traversaro traversaro Dec 10, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are you sure that the orientation changed? Those two set of RPY angles seems to correspond more and less to the same orientation matrix:

mamba create -n idyntreeenv -c conda-forge idyntree
mamba activate idyntreeenv
python
>>> import idyntree.bindings as idt
>>> idt.Rotation.RPY(1.5708,3.1415,0.0).toNumPy()
array([[-9.99999996e-01,  9.26535897e-05, -3.40335638e-10],
       [ 0.00000000e+00, -3.67320510e-06, -1.00000000e+00],
       [-9.26535897e-05, -9.99999996e-01,  3.67320509e-06]])
>>> idt.Rotation.RPY(-1.5707926535897934,9.265358979305728e-05,-3.141592653589793).toNumPy()
array([[-9.99999996e-01,  9.26535897e-05, -3.40335516e-10],
       [-1.22464679e-16, -3.67320510e-06, -1.00000000e+00],
       [-9.26535897e-05, -9.99999996e-01,  3.67320509e-06]])

Note that every single rotation matrix corresponds to multiple euler angles, so if you want to check for equality two set of euler angles you always need to first convert them to rotation matrices, you can't just compare the value of the euler angles.

@@ -872,7 +847,7 @@
<parent link="root_link"/>
<child link="r_hip_1"/>
<axis xyz=" 0. -1. 0."/>
<origin xyz="0.0216 -0.040549999999999996 0.0" rpy="0.0 0.0 0.0"/>
<origin xyz="0.0216 -0.040549999999999996 -0.021599999999999994" rpy="0.0 0.0 0.0"/>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Were these joint origins wrong?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fix it in 32f38dd

@@ -941,7 +916,7 @@
<parent link="root_link"/>
<child link="l_hip_1"/>
<axis xyz=" 0. -1. 0."/>
<origin xyz="0.0216 0.04045000000000001 0.0" rpy="0.0 0.0 0.0"/>
<origin xyz="0.0216 0.04045000000000001 -0.021599999999999994" rpy="0.0 0.0 0.0"/>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Were these joint origins wrong?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fix it in 32f38dd

@Nicogene Nicogene merged commit 4742522 into icub-tech-iit:master Dec 10, 2021
@Nicogene
Copy link
Member

Merged, thanks!

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

Successfully merging this pull request may close these issues.

4 participants