-
Notifications
You must be signed in to change notification settings - Fork 3
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
CREO2URDF – Use the OTK for getting the relevant information for the urdf #13
Comments
Today we started working here: #14 Right now we managed to:
About the last point we are not sure which one of these are needed for the urdf (cc @traversaro @fiorisi) Right now we are struggling on changing the unit of measure ( worst case we do the conversion mm->m by hand) and getting the axis/transformation parent-child without visiting the components in the assembly cc @pattacini |
Side note about the axis problem. But on the asm of ergocub instead is "nested" And getting the feature information we have I am afraid that this difference will need to access to it in different ways. @salvi-mattia @Mick3Lozzo @fiorisi can explain the differences in defining the mechanism? For now, we remain focused on mvp-1 and then on how it is defined in |
the second one is shrinkwrap made while we made tests in the past with @mfussi66 we had a first stint with creo parts and than a second with the shrinkwrapped parts |
Using CREO nomenclature and filling a bit the gaps as they do not provided a full description of this quantities or the rotation frame in which they are expressed, the However, it is a good idea to double check this assumptions. In particular, it is important to understand the orientation with which this inertia is expressed. For URDF/iDynTree, the inertia needs to be expressed with the orientation of the link frame, and in this case I am not sure which orientation are we using instead. The attribute of the inertial element in the URDF are the one expressed w.r.t. the center of mass (see http://wiki.ros.org/urdf/XML/link#Elements, https://github.com/robotology/idyntree/blob/cdfe1296960dfd87c53ea90fd131f456ea0ce48a/src/model_io/codecs/src/InertialElement.cpp#L104 and https://github.com/robotology/idyntree/blob/cdfe1296960dfd87c53ea90fd131f456ea0ce48a/src/model_io/codecs/src/URDFModelExport.cpp#L94). Small OT comment: I am quite curious about why they define what they call "inertia matrix" that is typically just used as as synonim of the "inertia tensor", I am not sure if they provide more details in the docs? |
When asking from creo the mass properties of a part thet inertia tensor are displayed as follow
Where |
I'm not sure that the csys of the part and the one used to represent the link in URDF coincide. |
Yes you should be able to specify a SYS, but if not specified should be the part origin. |
Yes indeed, @mfussi66 and I thought the same when we checked the urdf specification. |
Yes, see my comment in #13 (comment) . Anyhow, notice that it is also important to correctly specify the orientation of the frame where the inertia is expressed. |
Since we basically have all the informations to give to Unfortunately linking We will investigate it the next days |
I found this knowledge base article that says:
There is some help regarding that: |
Did you made sure that the iDynTree dll are in the |
Yes, but then I realized that probably was due to the fact we just added the idyntree lib dir of the conda environment to the PATH, but then probably the libraries linked by idyntree were not in the path and this triggered the error in loading the plugin in creo. We will try with a clean/proper installation of idyntree |
All the required |
This one! I could try with \bin |
It does work 🚀 |
Alonside @mfussi66, we managed to create our first idyntree model using the information retrieved by Creo, see 6fdbce2 We wanted also to export the urdf, but we had issues while using Only adding this line: iDynTree::ModelExporter mdl_exporter; triggers an error loading the plugin as when we put the wrong path in the PATH Even if we added In any case, we are very close to |
Linking Furthermore, to check if a .dll can found all the .dll on which it depends, you can try to open the Creo plugin in https://github.com/lucasg/Dependencies and check if there is any missing .dll . |
Setting
Where
|
Are you sure that I see that it is missing in both Working and not-working case, but probably that means that the |
|
This is my PATH:
This is what i got from
|
Can you use the |
Alongside @traversaro we continued the debugging but unfortunately, without finding a solution. We narrowed down the problem, and now just linking We tried:
All these tests have been done in a terminal where the PATH was set to the same used by Creo:
Here is the source of the #include <cstdlib>
#include <iomanip>
#include <iostream>
#include <iDynTree/ModelIO/ModelExporter.h>
#include <iDynTree/Model/Model.h>
#include <iDynTree/Model/RevoluteJoint.h>
#include <creo2urdf/Creo2Urdf.h>
#include <windows.h>
#include <iostream>
int main(int argc, char* argv[]) {
iDynTree::ModelExporter mdl_exporter;
iDynTree::Model idyn_model;
std::cout<<"This is Val "<<hello(val)<<std::endl;
HINSTANCE hGetProcIDDLL = LoadLibrary("C:\\Users\\ngenesio\\icub-tech-iit\\creo2urdf\\build\\x64-Release\\bin\\creo2urdf.dll");
if (!hGetProcIDDLL) {
std::cout << "could not load the dynamic library" << std::endl;
return EXIT_FAILURE;
}
else {
std::cout << "Library loaded!" << std::endl;
}
/*...*/
return EXIT_SUCCESS; Our option are now:
|
Thanks to the precious help of @traversaro I managed to link statically I added them in the readme, see 8df332c And now habemus urdf! 🎸 <?xml version="1.0"?>
<robot name="2BARS">
<link name="BAR">
<inertial>
<mass value="0.00741938044781609"/>
<origin xyz="0 -15 3.5" rpy="0 -0 0"/>
<inertia ixx="-0.8349706673190365" ixy="0" ixz="0" iyy="-0.001970110919505899" iyz="-0.3895174735103447" izz="-0.7157575641017974"/>
</inertial>
</link>
<joint name="BAR--BARLONGER" type="continuous">
<origin xyz="0 0 6.811996306092723e-15" rpy="0 -0 -0.7060878385670463"/>
<axis xyz="0 0 1"/>
<parent link="BAR"/>
<child link="BARLONGER"/>
</joint>
<link name="BARLONGER">
<inertial>
<mass value="0.010359380471568048"/>
<origin xyz="0 -22.5 3.5" rpy="0 -0 0"/>
<inertia ixx="-2.904730637223145" ixy="-2.2498100353314738e-6" ixz="0" iyy="-0.001479921769347553" iyz="-0.8158012121359837" izz="-2.7370073443897516"/>
</inertial>
</link>
</robot> The next point will be to add the visuals to the urdf, here is some useful links:
cc @mfussi66 @pattacini @maggia80 @fiorisi @salvi-mattia @Mick3Lozzo |
Today I committed some fixes/enhancements: For the latter point in iDynTree if a joint has no limits it is considered <?xml version="1.0"?>
<robot name="2BARS">
<link name="BAR">
<inertial>
<mass value="0.00741938044781609"/>
<origin xyz="0 -0.015 0.0035" rpy="0 -0 0"/>
<inertia ixx="-8.349706673190367e-7" ixy="0" ixz="0" iyy="-1.970110919505906e-9" iyz="-3.895174735103447e-7" izz="-7.157575641017976e-7"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<geometry>
<mesh filename="BAR.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<geometry>
<mesh filename="BAR.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</collision>
</link>
<joint name="BAR--BARLONGER" type="revolute">
<origin xyz="0 0 6.811996306092723e-18" rpy="0 -0 -0.7060878385670463"/>
<axis xyz="0 0 1"/>
<parent link="BAR"/>
<child link="BARLONGER"/>
<limit lower="0" upper="3.141592653589793" effort="1e+9" velocity="1e+9"/>
</joint>
<link name="BARLONGER">
<inertial>
<mass value="0.010359380471568048"/>
<origin xyz="0 -0.0225 0.0035" rpy="0 -0 0"/>
<inertia ixx="-2.9047306372231453e-6" ixy="-2.249810035331474e-12" ixz="0" iyy="-1.4799217693475475e-9" iyz="-8.158012121359838e-7" izz="-2.7370073443897514e-6"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<geometry>
<mesh filename="BARLONGER.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0"/>
<geometry>
<mesh filename="BARLONGER.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</collision>
</link>
</robot>
I think we can consider this activity done and open a followup with the remaining points |
A comment for future activities, probably a bit OT here but I do not know where to write it otherwise. Probably before scaling up in complexity you may want to check if the revolute joint is exported as expected? If we have a way to vary he joint angle in Creo, a possible end-to-end check is to compute the transform between |
Good point, I think that the next activity will be mostly focused on validation on what we got |
Task description
This is the follow-up of #11.
We would like to:
Definition of done
The above list is completed
The text was updated successfully, but these errors were encountered: