Skip to content
Open
Show file tree
Hide file tree
Changes from all 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
1 change: 1 addition & 0 deletions urdf_parser/include/urdf_parser/urdf_parser.h
Original file line number Diff line number Diff line change
Expand Up @@ -174,6 +174,7 @@ class URDFVersion final
namespace urdf{
URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDF(const std::string &xml_string);
URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDFFile(const std::string &path);
URDFDOM_DLLAPI std::string exportURDF(const ModelInterface &model);
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

the exportURDF API was deprecated in #191 and removed in #217

what is it used for?

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

I tthink they are used to export the string from a Model, but not much use. If this is the case, then there needs to be other cleanups to be done. Should I do the cleanup part?

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

I don't think this is a breaking change, so we can merge to rolling after the freeze date and then backport to lyrical after the initial release

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

I tthink they are used to export the string from a Model, but not much use. If this is the case, then there needs to be other cleanups to be done. Should I do the cleanup part?

maybe create an issue to describe the cleanup work to be done and what it will enable?

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

Copy that

}

#endif
13 changes: 13 additions & 0 deletions urdf_parser/src/link.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -584,6 +584,15 @@ bool exportCylinder(Cylinder &y, tinyxml2::XMLElement *xml)
return true;
}

bool exportCapsule(Capsule &c, tinyxml2::XMLElement *xml)
{
tinyxml2::XMLElement *capsule_xml = xml->GetDocument()->NewElement("capsule");
capsule_xml->SetAttribute("radius", urdf_export_helpers::values2str(c.radius).c_str());
capsule_xml->SetAttribute("length", urdf_export_helpers::values2str(c.length).c_str());
xml->LinkEndChild(capsule_xml);
return true;
}

bool exportMesh(Mesh &m, tinyxml2::XMLElement *xml)
{
// e.g. add <mesh filename="my_file" scale="1 1 1"/>
Expand Down Expand Up @@ -614,6 +623,10 @@ bool exportGeometry(GeometrySharedPtr &geom, tinyxml2::XMLElement *xml)
{
exportMesh((*(urdf::dynamic_pointer_cast<Mesh>(geom).get())), geometry_xml);
}
else if (urdf::dynamic_pointer_cast<Capsule>(geom))
{
exportCapsule((*(urdf::dynamic_pointer_cast<Capsule>(geom).get())), geometry_xml);
}
else
{
CONSOLE_BRIDGE_logError("geometry not specified, I'll make one up for you!");
Expand Down
10 changes: 10 additions & 0 deletions urdf_parser/src/model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,7 @@ tinyxml2::XMLDocument* exportURDFInternal(const ModelInterface &model)

tinyxml2::XMLElement* robot = doc->NewElement("robot");
robot->SetAttribute("name", model.name_.c_str());
robot->SetAttribute("version", "1.2");
doc->LinkEndChild(robot);


Expand All @@ -312,4 +313,13 @@ tinyxml2::XMLDocument* exportURDFInternal(const ModelInterface &model)

return doc;
}

URDFDOM_DLLAPI std::string exportURDF(const ModelInterface &model)
{
tinyxml2::XMLDocument *doc = exportURDFInternal(model);
tinyxml2::XMLPrinter printer;
doc->Print(&printer);
delete doc;
return printer.CStr();
}
}
46 changes: 46 additions & 0 deletions urdf_parser/test/urdf_schema_capsule_geometry_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <gtest/gtest.h>
#include <cmath>
#include <memory>
#include <string>

#include "urdf_model/link.h"
#include "urdf_parser/urdf_parser.h"
Expand Down Expand Up @@ -266,6 +267,51 @@ TEST(URDF_UNIT_TEST, parse_multiple_capsules_in_same_link)
EXPECT_DOUBLE_EQ(2.0, collision_capsule_1->length);
}

TEST(URDF_UNIT_TEST, export_capsule_geometry_round_trip)
{
std::string urdf_str = R"urdf(
<robot name="capsule_export_test" version="1.1">
<link name="link1">
<visual>
<origin xyz="0.1 0.2 0.3" rpy="0 0 0"/>
<geometry>
<capsule radius="0.05" length="0.5"/>
</geometry>
</visual>
<collision>
<geometry>
<capsule radius="0.1" length="1.0"/>
</geometry>
</collision>
</link>
</robot>
)urdf";

urdf::ModelInterfaceSharedPtr model = urdf::parseURDF(urdf_str);
ASSERT_NE(nullptr, model);

std::string exported = urdf::exportURDF(*model);
ASSERT_FALSE(exported.empty());

urdf::ModelInterfaceSharedPtr reparsed = urdf::parseURDF(exported);
ASSERT_NE(nullptr, reparsed);

urdf::LinkConstSharedPtr link = reparsed->getLink("link1");
ASSERT_NE(nullptr, link);

ASSERT_EQ(1u, link->visual_array.size());
auto visual_capsule = std::dynamic_pointer_cast<urdf::Capsule>(link->visual_array[0]->geometry);
ASSERT_NE(nullptr, visual_capsule);
EXPECT_DOUBLE_EQ(0.05, visual_capsule->radius);
EXPECT_DOUBLE_EQ(0.5, visual_capsule->length);

ASSERT_EQ(1u, link->collision_array.size());
auto collision_capsule = std::dynamic_pointer_cast<urdf::Capsule>(link->collision_array[0]->geometry);
ASSERT_NE(nullptr, collision_capsule);
EXPECT_DOUBLE_EQ(0.1, collision_capsule->radius);
EXPECT_DOUBLE_EQ(1.0, collision_capsule->length);
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
Expand Down
Loading