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

Add minimal example, remove creopyson test #76

Merged
merged 7 commits into from
Feb 6, 2024
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 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
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
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;
}
}
}

Copy link
Member

Choose a reason for hiding this comment

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

This is not used anywhere since we refactored the code for using the ElementTree right?

Copy link
Member Author

Choose a reason for hiding this comment

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

Exactly!

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
46 changes: 34 additions & 12 deletions src/creo2urdf/src/Utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,19 @@ void sanitizeSTL(std::string stl)
output.close();
}

/**
* @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) {

iDynTree::Transform H_child = iDynTree::Transform::Identity();
Expand All @@ -173,12 +186,16 @@ 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>
* @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 Expand Up @@ -230,13 +247,18 @@ std::pair<bool, iDynTree::Transform> getTransformFromPart(pfcModel_ptr modelhdl,
}

/**
* @brief Get the Rotation Axis From Part object
* @brief Retrieves the unit vector representing the specified axis in the given part.
*
* @param modelhdl
* @param axis_name
* @param link_frame_name
* @param scale
* @return std::pair<bool, iDynTree::Direction>
* @param modelhdl The part model.
* @param axis_name The name of the axis to retrieve.
* @param link_frame_name The name of the coordinate system in which the axis unit vector should be expressed.
* @param scale scaling factor for expressing the position of the transform.
*
* @return A std::pair<bool, iDynTree::Direction> containing the result of the operation:
* - The first element is a boolean indicating success (true) or failure (false).
* - The second element is an iDynTree::Direction representing the unit vector of the specified axis
* transformed into the coordinate system of the specified link frame. If the operation fails,
* this vector will be zero-initialized.
*/
Copy link
Member

Choose a reason for hiding this comment

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

I would move the doxygen documentation to the Utils.h, if I recall correctly the doxyfile has a filter for getting only the .h/.hpp

Copy link
Member Author

Choose a reason for hiding this comment

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

removed it from the cpp, for some reason it was there.

std::pair<bool, iDynTree::Direction> getAxisFromPart(pfcModel_ptr modelhdl, const std::string& axis_name, const string& link_frame_name, const array<double, 3>& scale) {

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

This file was deleted.