Skip to content

Commit

Permalink
Add minimal example, remove creopyson test (#76)
Browse files Browse the repository at this point in the history
  • Loading branch information
mfussi66 authored Feb 6, 2024
1 parent 55a1654 commit 3d72a45
Show file tree
Hide file tree
Showing 11 changed files with 39 additions and 189 deletions.
10 changes: 10 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,9 @@ This archive contains the dll of the plugin and the `text` folder for running it
## Installation from sources

### Dependencies

Right now the `creo2urdf` plugin needs its dependencies to be compiled and linked **statically**:

- Download [vcpkg](https://github.com/microsoft/vcpkg): `git clone https://github.com/microsoft/vcpkg`
- Bootstrap vcpkg: `.\vcpkg\bootstrap-vcpkg.bat`
- Run `[path to vcpkg]/vcpkg install --triplet x64-windows-static-md eigen3 yaml-cpp rapidcsv libxml2 assimp`
Expand Down Expand Up @@ -61,6 +63,14 @@ END

- Select a yaml and csv configuration files with a format explained in the following sections, and the folder where the urdf and the meshes will be saved.


### Test your installation
The folder `examples` contains a simple assembly with two links, called 2BARS.asm.
You can open the assembly in Creo and then test the installation by clicking on the Creo2Urdf button.
The plugin will ask you to select the related .yaml and .csv files, which are provided in the folder.

If the export process was successful, you should see three files": "bar.stl", "barlonger.stl" and "model.urdf".

### YAML Parameter File
The YAML format is used to pass parameters to the plugin to customized the conversion process.
The parameter accepted by the plugin are documented in the following.
Expand Down
Binary file added examples/2bars/2bars.asm
Binary file not shown.
1 change: 1 addition & 0 deletions examples/2bars/2bars.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
joint_name,lower_limit,upper_limit,damping,friction,velocity_limit,effort_limit
3 changes: 3 additions & 0 deletions examples/2bars/2bars.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
robotName: 2bars
scale: [0.001,0.001,0.001]
root: BAR
Binary file added examples/2bars/bar.prt
Binary file not shown.
Binary file added examples/2bars/barlonger.prt
Binary file not shown.
6 changes: 0 additions & 6 deletions src/creo2urdf/include/creo2urdf/Creo2Urdf.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,12 +81,6 @@ class Creo2Urdf : public pfcUICommandActionListener {
*/
iDynTree::SpatialInertia computeSpatialInertiafromCreo(pfcMassProperty_ptr mass_prop, iDynTree::Transform H, const std::string& link_name);

/**
* @brief Populate the joint information map from the Creo model handle.
* @param modelhdl The Creo model handle.
*/
void populateJointInfoMap(pfcModel_ptr modelhdl);

/**
* @brief Populate the exported frame information map from the Creo model handle.
* @param modelhdl The Creo model handle.
Expand Down
34 changes: 21 additions & 13 deletions src/creo2urdf/include/creo2urdf/Utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -399,23 +399,31 @@ void printRotationMatrix(pfcMatrix3D_ptr m);
void sanitizeSTL(std::string stl);

/**
* @brief Get the 3D Transform From Root frame of the assembly (parent) to the frame of the selected model (child)
*
* @param comp_path The component path of the assembly from the asm to the selected model
* @param modelhdl The model handle that contains link_frame_name
* @param link_frame_name The name of the frame belonging to modelhdl
* @param scale The scaling factor for the origin of the child frame
* @return std::pair<bool, iDynTree::Transform> Pair containing a success/failure flag, and a 3D transform in iDynTree format
* @brief Retrieves the transformation from the root to a specified link frame in the context of a component path.
*
* @param comp_path component path that represents the assembly hierarchy.
* @param modelhdl The part model in which the link frame is defined.
* @param link_frame_name The name of the link frame for which the transformation is requested.
* @param scale scaling factor for expressing the position of the transform.
*
* @return A std::pair<bool, iDynTree::Transform> containing the result of the operation:
* - The first element is a boolean indicating success (true) or failure (false).
* - The second element is an iDynTree::Transform representing the transformation from the root to the specified link frame.
* If the operation fails, this transformation will be an identity transformation.
*/
std::pair<bool, iDynTree::Transform> getTransformFromRootToChild(pfcComponentPath_ptr comp_path, pfcModel_ptr modelhdl, const std::string& link_frame_name, const array<double, 3>& scale);

/**
* @brief Get the 3D Transform From Root frame of the part (parent) to the frame of the selected model (child)
*
* @param modelhdl The model handle that contains link_frame_name
* @param link_frame_name The name of the frame belonging to modelhdl
* @param scale The scaling factor for the origin of the child frame
* @return std::pair<bool, iDynTree::Transform> Pair containing a success/failure flag, and a 3D transform in iDynTree format
* @brief Retrieves the transformation matrix representing the coordinate system of a specified link frame in the given part.
*
* @param modelhdl The part model.
* @param link_frame_name The name of the link frame for which the transformation matrix is requested.
* @param scale scaling factor for expressing the position of the transform.
*
* @return A std::pair<bool, iDynTree::Transform> containing the result of the operation:
* - The first element is a boolean indicating success (true) or failure (false).
* - The second element is an iDynTree::Transform representing the transformation matrix of the specified link frame.
* If the operation fails, this transformation matrix will be an identity matrix.
*/
std::pair<bool, iDynTree::Transform> getTransformFromPart(pfcModel_ptr modelhdl, const std::string& link_frame_name, const array<double, 3>& scale);

Expand Down
74 changes: 4 additions & 70 deletions src/creo2urdf/src/Creo2Urdf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,6 @@ void Creo2Urdf::OnCommand() {

// Now we have to add joints to the iDynTree model

//printToMessageWindow("Axis info map has size " + to_string(joint_info_map.size()));
for (auto & joint_info : joint_info_map) {
auto parent_link_name = joint_info.second.parent_link_name;
auto child_link_name = joint_info.second.child_link_name;
Expand All @@ -195,6 +194,7 @@ void Creo2Urdf::OnCommand() {
parent_H_child = root_H_parent_link.inverse() * root_H_child_link;

if (joint_info.second.type == JointType::Revolute || joint_info.second.type == JointType::Linear) {

iDynTree::Direction axis;
std::tie(ret, axis) = getAxisFromPart(parent_model, axis_name, parent_link_frame, scale);

Expand All @@ -203,7 +203,8 @@ void Creo2Urdf::OnCommand() {
return;
}

if (config["reverseRotationAxis"].Scalar().find(joint_name) != std::string::npos)
if (config["reverseRotationAxis"].IsDefined() &&
config["reverseRotationAxis"].Scalar().find(joint_name) != std::string::npos)
{
axis = axis.reverse();
}
Expand Down Expand Up @@ -403,73 +404,6 @@ iDynTree::SpatialInertia Creo2Urdf::computeSpatialInertiafromCreo(pfcMassPropert
return sp_inertia;
}

void Creo2Urdf::populateJointInfoMap(pfcModel_ptr modelhdl) {

// The revolute joints are defined by aligning along the
// rotational axis

auto axes_list = modelhdl->ListItems(pfcModelItemType::pfcITEM_AXIS);
auto link_name = string(modelhdl->GetFullName());
// printToMessageWindow("There are " + to_string(axes_list->getarraysize()) + " axes");
if (axes_list->getarraysize() == 0) {
printToMessageWindow("There is no AXIS in the part " + link_name, c2uLogLevel::WARN);
}

pfcAxis* axis = nullptr;

for (size_t i = 0; i < axes_list->getarraysize(); i++)
{
auto axis_elem = pfcAxis::cast(axes_list->get(xint(i)));
auto axis_name_str = string(axis_elem->GetName());
JointInfo joint_info;
joint_info.datum_name = axis_name_str;
joint_info.type = JointType::Revolute;
if (joint_info_map.find(axis_name_str) == joint_info_map.end()) {
joint_info.parent_link_name = link_name;
joint_info_map.insert(std::make_pair(axis_name_str, joint_info));
}
else {
auto& existing_joint_info = joint_info_map.at(axis_name_str);
// The child_link_name field should be empty, otherwise it means that we have clash of axis names, let's prevent it
if (existing_joint_info.child_link_name.empty()) {
existing_joint_info.child_link_name = link_name;
}
else
{
printToMessageWindow(axis_name_str + " defines already a revolute joint! Please check the cad.", c2uLogLevel::WARN);
}
}
}

// The fixed joint right now is defined making coincident the csys.
auto csys_list = modelhdl->ListItems(pfcModelItemType::pfcITEM_COORD_SYS);

if (csys_list->getarraysize() == 0) {
printToMessageWindow("There is no CSYS in the part " + link_name, c2uLogLevel::WARN);
}

for (xint i = 0; i < csys_list->getarraysize(); i++)
{
auto csys_name = string(csys_list->get(i)->GetName());
// We need to discard "general" csys, such as CSYS and ASM_CSYS
if (csys_name.find("SCSYS") == std::string::npos) {
continue;
}

JointInfo joint_info;
joint_info.datum_name = csys_name;
joint_info.type = JointType::Fixed;
if (joint_info_map.find(csys_name) == joint_info_map.end()) {
joint_info.parent_link_name = link_name;
joint_info_map.insert(std::make_pair(csys_name, joint_info));
}
else {
auto& existing_joint_info = joint_info_map.at(csys_name);
existing_joint_info.child_link_name = link_name;
}
}
}

void Creo2Urdf::populateExportedFrameInfoMap(pfcModel_ptr modelhdl) {

// The revolute joints are defined by aligning along the
Expand Down Expand Up @@ -608,7 +542,7 @@ bool Creo2Urdf::addMeshAndExport(pfcModel_ptr component_handle, const std::strin
}

// Make all alphabetic characters lowercase
if (config["forcelowercase"].as<bool>())
if (config["forcelowercase"].IsDefined() && config["forcelowercase"].as<bool>())
{
std::transform(link_name.begin(), link_name.end(), link_name.begin(),
[](unsigned char c) { return std::tolower(c); });
Expand Down
66 changes: 0 additions & 66 deletions src/creo2urdf/src/Utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,6 @@

#include <creo2urdf/Utils.h>

/**
* @brief Computes the unit vector of a Creo Axis.
* The axis is defined by start and end point, and the magnitude is normalized.
*
* @param axis_data The axis datum as a CurveDescriptor
* @return std::array<double, 3> The resulting normalized unit vector
*/
std::array<double, 3> computeUnitVectorFromAxis(pfcCurveDescriptor_ptr axis_data)
{
auto axis_line = pfcLineDescriptor::cast(axis_data); // cursed cast from hell
Expand All @@ -43,14 +36,6 @@ std::array<double, 3> computeUnitVectorFromAxis(pfcCurveDescriptor_ptr axis_data
return unit_vector;
}

/**
* @brief Converts a 3D Creo transform into iDynTree transform. The position is defined as a 3-elements vector in m,
* and rotation is represented as a SO(3) matrix for both representations.
*
* @param creo_trf The 3D transform to convert
* @param scale The factor used to scale the position vector (e.g. from m to mm)
* @return iDynTree::Transform
*/
iDynTree::Transform fromCreo(pfcTransform3D_ptr creo_trf, const array<double, 3>& scale)
{
iDynTree::Transform idyn_trf;
Expand All @@ -64,13 +49,6 @@ iDynTree::Transform fromCreo(pfcTransform3D_ptr creo_trf, const array<double, 3>
return idyn_trf;
}

/**
* @brief Get the datums defined in a Solid depending on the selected type
*
* @param solid The solid in which to query the datums
* @param type The type of datums to extract as model items
* @return std::vector<string> A vector of datum names
*/
std::vector<string> getSolidDatumNames(pfcSolid_ptr solid, pfcModelItemType type)
{
std::vector<string> result;
Expand All @@ -88,15 +66,6 @@ std::vector<string> getSolidDatumNames(pfcSolid_ptr solid, pfcModelItemType type
return result;
}

/**
* @brief Prints a string to the message window on the bottom part of the Creo Parametric UI.
* The message can have different log levels, represented by an icon on its left side.
* The available log levels are defined in text/usascii/creo2urdf.txt.
*
* @param message The desired message to be printed
* @param log_level The desired log level. Can be NONE, INFO, WARN, PROMPT.
* The PROMPT enum requires user input to proceed. The user input is not processed yet.
*/
void printToMessageWindow(std::string message, c2uLogLevel log_level)
{
pfcSession_ptr session_ptr = pfcGetProESession();
Expand All @@ -106,36 +75,18 @@ void printToMessageWindow(std::string message, c2uLogLevel log_level)
session_ptr->UIDisplayMessage("creo2urdf.txt", log_level_key.at(log_level).c_str(), msg_sequence);
}

/**
* @brief Prints to the message window a Creo 3D transform in both origin and orientation
* using the iDynTree representation
*
* @param m The Creo 3D transform to print
*/
void printTransformMatrix(pfcTransform3D_ptr m)
{
printToMessageWindow(fromCreo(m).toString());
}

/**
* @brief Prints to the message window a Creo 3D rotation matrix in SO(3)
*
* @param m The Creo 3D transform to print
*/
void printRotationMatrix(pfcMatrix3D_ptr m)
{
printToMessageWindow(to_string(m->get(0, 0)) + " " + to_string(m->get(0, 1)) + " " + to_string(m->get(0, 2)));
printToMessageWindow(to_string(m->get(1, 0)) + " " + to_string(m->get(1, 1)) + " " + to_string(m->get(1, 2)));
printToMessageWindow(to_string(m->get(2, 0)) + " " + to_string(m->get(2, 1)) + " " + to_string(m->get(2, 2)));
}

/**
* @brief Replaces the first 5 bytes of a binary STL file with the string "robot".
* This is necessary to avoid accidental parsing of the file as ASCII.
* For details, see https://github.com/icub-tech-iit/creo2urdf/issues/16
*
* @param stl Path of the STL file to edit
*/
void sanitizeSTL(std::string stl)
{
size_t n_bytes = 5;
Expand Down Expand Up @@ -172,14 +123,6 @@ std::pair<bool, iDynTree::Transform> getTransformFromRootToChild(pfcComponentPat

}

/**
* @brief Get the Transform From Part object
*
* @param modelhdl
* @param link_frame_name
* @param scale
* @return std::pair<bool, iDynTree::Transform>
*/
std::pair<bool, iDynTree::Transform> getTransformFromPart(pfcModel_ptr modelhdl, const std::string& link_frame_name, const array<double, 3>& scale) {

iDynTree::Transform H_child;
Expand Down Expand Up @@ -229,15 +172,6 @@ std::pair<bool, iDynTree::Transform> getTransformFromPart(pfcModel_ptr modelhdl,
return { false, H_child };
}

/**
* @brief Get the Rotation Axis From Part object
*
* @param modelhdl
* @param axis_name
* @param link_frame_name
* @param scale
* @return std::pair<bool, iDynTree::Direction>
*/
std::pair<bool, iDynTree::Direction> getAxisFromPart(pfcModel_ptr modelhdl, const std::string& axis_name, const string& link_frame_name, const array<double, 3>& scale) {

iDynTree::Direction axis_unit_vector;
Expand Down
34 changes: 0 additions & 34 deletions src/examples/creopyson/creopyson_example.py

This file was deleted.

0 comments on commit 3d72a45

Please sign in to comment.