diff --git a/tesseract_urdf/test/tesseract_urdf_box_unit.cpp b/tesseract_urdf/test/tesseract_urdf_box_unit.cpp
index 15d7fb9fefe..db61588979c 100644
--- a/tesseract_urdf/test/tesseract_urdf_box_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_box_unit.cpp
@@ -13,7 +13,8 @@ TEST(TesseractURDFUnit, parse_box) // NOLINT
{
std::string str = R"()";
tesseract_geometry::Box::Ptr geom;
- EXPECT_TRUE(runTest(geom, &tesseract_urdf::parseBox, str, "box", 2));
+ EXPECT_TRUE(
+ runTest(geom, &tesseract_urdf::parseBox, str, tesseract_urdf::BOX_ELEMENT_NAME));
EXPECT_NEAR(geom->getX(), 1, 1e-8);
EXPECT_NEAR(geom->getY(), 2, 1e-8);
EXPECT_NEAR(geom->getZ(), 3, 1e-8);
@@ -22,7 +23,8 @@ TEST(TesseractURDFUnit, parse_box) // NOLINT
{ // https://github.com/ros-industrial-consortium/tesseract_ros/issues/67
std::string str = R"()";
tesseract_geometry::Box::Ptr geom;
- EXPECT_TRUE(runTest(geom, &tesseract_urdf::parseBox, str, "box", 2));
+ EXPECT_TRUE(
+ runTest(geom, &tesseract_urdf::parseBox, str, tesseract_urdf::BOX_ELEMENT_NAME));
EXPECT_NEAR(geom->getX(), 0.5, 1e-8);
EXPECT_NEAR(geom->getY(), 0.25, 1e-8);
EXPECT_NEAR(geom->getZ(), 0.75, 1e-8);
@@ -31,37 +33,43 @@ TEST(TesseractURDFUnit, parse_box) // NOLINT
{
std::string str = R"()";
tesseract_geometry::Box::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseBox, str, "box", 2));
+ EXPECT_FALSE(
+ runTest(geom, &tesseract_urdf::parseBox, str, tesseract_urdf::BOX_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_geometry::Box::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseBox, str, "box", 2));
+ EXPECT_FALSE(
+ runTest(geom, &tesseract_urdf::parseBox, str, tesseract_urdf::BOX_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_geometry::Box::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseBox, str, "box", 2));
+ EXPECT_FALSE(
+ runTest(geom, &tesseract_urdf::parseBox, str, tesseract_urdf::BOX_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_geometry::Box::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseBox, str, "box", 2));
+ EXPECT_FALSE(
+ runTest(geom, &tesseract_urdf::parseBox, str, tesseract_urdf::BOX_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_geometry::Box::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseBox, str, "box", 2));
+ EXPECT_FALSE(
+ runTest(geom, &tesseract_urdf::parseBox, str, tesseract_urdf::BOX_ELEMENT_NAME));
}
{
std::string str = "";
tesseract_geometry::Box::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseBox, str, "box", 2));
+ EXPECT_FALSE(
+ runTest(geom, &tesseract_urdf::parseBox, str, tesseract_urdf::BOX_ELEMENT_NAME));
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_calibration_unit.cpp b/tesseract_urdf/test/tesseract_urdf_calibration_unit.cpp
index 4f0f7dd9658..29144f62714 100644
--- a/tesseract_urdf/test/tesseract_urdf_calibration_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_calibration_unit.cpp
@@ -14,7 +14,7 @@ TEST(TesseractURDFUnit, parse_calibration) // NOLINT
std::string str = R"()";
tesseract_scene_graph::JointCalibration::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseCalibration, str, "calibration", 2));
+ elem, &tesseract_urdf::parseCalibration, str, tesseract_urdf::CALIBRATION_ELEMENT_NAME));
EXPECT_NEAR(elem->rising, 1, 1e-8);
EXPECT_NEAR(elem->falling, 2, 1e-8);
}
@@ -23,7 +23,7 @@ TEST(TesseractURDFUnit, parse_calibration) // NOLINT
std::string str = R"()";
tesseract_scene_graph::JointCalibration::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseCalibration, str, "calibration", 2));
+ elem, &tesseract_urdf::parseCalibration, str, tesseract_urdf::CALIBRATION_ELEMENT_NAME));
EXPECT_NEAR(elem->rising, 1, 1e-8);
EXPECT_NEAR(elem->falling, 0, 1e-8);
}
@@ -32,7 +32,7 @@ TEST(TesseractURDFUnit, parse_calibration) // NOLINT
std::string str = R"()";
tesseract_scene_graph::JointCalibration::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseCalibration, str, "calibration", 2));
+ elem, &tesseract_urdf::parseCalibration, str, tesseract_urdf::CALIBRATION_ELEMENT_NAME));
EXPECT_NEAR(elem->rising, 0, 1e-8);
EXPECT_NEAR(elem->falling, 2, 1e-8);
}
@@ -41,21 +41,21 @@ TEST(TesseractURDFUnit, parse_calibration) // NOLINT
std::string str = R"()";
tesseract_scene_graph::JointCalibration::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseCalibration, str, "calibration", 2));
+ elem, &tesseract_urdf::parseCalibration, str, tesseract_urdf::CALIBRATION_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_scene_graph::JointCalibration::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseCalibration, str, "calibration", 2));
+ elem, &tesseract_urdf::parseCalibration, str, tesseract_urdf::CALIBRATION_ELEMENT_NAME));
}
{
std::string str = "";
tesseract_scene_graph::JointCalibration::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseCalibration, str, "calibration", 2));
+ elem, &tesseract_urdf::parseCalibration, str, tesseract_urdf::CALIBRATION_ELEMENT_NAME));
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_capsule_unit.cpp b/tesseract_urdf/test/tesseract_urdf_capsule_unit.cpp
index 4565dd93a88..e7da8f2434d 100644
--- a/tesseract_urdf/test/tesseract_urdf_capsule_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_capsule_unit.cpp
@@ -11,70 +11,79 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
TEST(TesseractURDFUnit, parse_capsule) // NOLINT
{
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_TRUE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_TRUE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
EXPECT_NEAR(geom->getRadius(), 1, 1e-8);
EXPECT_NEAR(geom->getLength(), 2, 1e-8);
}
{ // https://github.com/ros-industrial-consortium/tesseract_ros/issues/67
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_TRUE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_TRUE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
EXPECT_NEAR(geom->getRadius(), 0.25, 1e-8);
EXPECT_NEAR(geom->getLength(), 0.5, 1e-8);
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
}
// TODO: I would expect this to fail but tinyxml2 still parses it so need to create an issue.
// {
- // std::string str = R"()";
+ // std::string str = R"()";
// tesseract_geometry::Capsule::Ptr geom;
- // auto status = runTest(geom, str, "capsule");
+ // auto status = runTest(geom, str, tesseract_urdf::CAPSULE_ELEMENT_NAME);
// EXPECT_FALSE(*status);
// EXPECT_FALSE(status->message().empty());
// }
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
}
{
- std::string str = "";
+ std::string str = "";
tesseract_geometry::Capsule::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCapsule, str, "capsule", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCapsule, str, tesseract_urdf::CAPSULE_ELEMENT_NAME));
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_collision_unit.cpp b/tesseract_urdf/test/tesseract_urdf_collision_unit.cpp
index 668da446887..fc1087c2cf4 100644
--- a/tesseract_urdf/test/tesseract_urdf_collision_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_collision_unit.cpp
@@ -23,7 +23,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT
)";
tesseract_scene_graph::Collision::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseCollision, str, "collision", resource_locator, 2));
+ elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator));
EXPECT_TRUE(elem->geometry != nullptr);
EXPECT_FALSE(elem->origin.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
}
@@ -36,7 +36,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT
)";
tesseract_scene_graph::Collision::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseCollision, str, "collision", resource_locator, 2));
+ elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator));
EXPECT_TRUE(elem->geometry != nullptr);
EXPECT_TRUE(elem->origin.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
}
@@ -49,7 +49,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT
)";
tesseract_scene_graph::Collision::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseCollision, str, "collision", resource_locator, 2));
+ elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator));
EXPECT_TRUE(elem->geometry != nullptr);
EXPECT_TRUE(elem->origin.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
EXPECT_TRUE(elem->geometry->getType() == tesseract_geometry::GeometryType::COMPOUND_MESH);
@@ -65,7 +65,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT
)";
tesseract_scene_graph::Collision::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseCollision, str, "collision", resource_locator, 2));
+ elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator));
EXPECT_TRUE(elem == nullptr);
}
@@ -77,7 +77,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT
)";
tesseract_scene_graph::Collision::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseCollision, str, "collision", resource_locator, 2));
+ elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator));
EXPECT_TRUE(elem == nullptr);
}
@@ -86,7 +86,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT
)";
tesseract_scene_graph::Collision::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseCollision, str, "collision", resource_locator, 2));
+ elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator));
EXPECT_TRUE(elem == nullptr);
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_common_unit.h b/tesseract_urdf/test/tesseract_urdf_common_unit.h
index fc32790de86..e6abc50b1c0 100644
--- a/tesseract_urdf/test/tesseract_urdf_common_unit.h
+++ b/tesseract_urdf/test/tesseract_urdf_common_unit.h
@@ -19,10 +19,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
template
bool runTest(ElementType& type,
- std::function func,
+ std::function func,
const std::string& xml_string,
- const std::string& element_name,
- int version)
+ const std::string& element_name)
{
tinyxml2::XMLDocument xml_doc;
EXPECT_TRUE(xml_doc.Parse(xml_string.c_str()) == tinyxml2::XML_SUCCESS);
@@ -32,7 +31,7 @@ bool runTest(ElementType& type,
try
{
- type = func(element, version);
+ type = func(element);
}
catch (const std::exception& e)
{
@@ -46,12 +45,10 @@ bool runTest(ElementType& type,
template
bool runTest(
ElementType& type,
- std::function
- func,
+ std::function func,
const std::string& xml_string,
const std::string& element_name,
const tesseract_common::ResourceLocator& locator,
- int version,
bool visual)
{
tinyxml2::XMLDocument xml_doc;
@@ -62,7 +59,7 @@ bool runTest(
try
{
- type = func(element, locator, visual, version);
+ type = func(element, locator, visual);
}
catch (const std::exception& e)
{
@@ -74,13 +71,11 @@ bool runTest(
}
template
-bool runTest(
- ElementType& type,
- std::function func,
- const std::string& xml_string,
- const std::string& element_name,
- const tesseract_common::ResourceLocator& locator,
- int version)
+bool runTest(ElementType& type,
+ std::function func,
+ const std::string& xml_string,
+ const std::string& element_name,
+ const tesseract_common::ResourceLocator& locator)
{
tinyxml2::XMLDocument xml_doc;
EXPECT_TRUE(xml_doc.Parse(xml_string.c_str()) == tinyxml2::XML_SUCCESS);
@@ -90,7 +85,7 @@ bool runTest(
try
{
- type = func(element, locator, version);
+ type = func(element, locator);
}
catch (const std::exception& e)
{
@@ -105,13 +100,11 @@ template
bool runTest(ElementType& type,
std::function&,
- const int)> func,
+ std::unordered_map&)> func,
const std::string& xml_string,
const std::string& element_name,
const tesseract_common::ResourceLocator& locator,
- std::unordered_map& available_materials,
- int version)
+ std::unordered_map& available_materials)
{
tinyxml2::XMLDocument xml_doc;
EXPECT_TRUE(xml_doc.Parse(xml_string.c_str()) == tinyxml2::XML_SUCCESS);
@@ -121,7 +114,7 @@ bool runTest(ElementType& type,
try
{
- type = func(element, locator, available_materials, version);
+ type = func(element, locator, available_materials);
}
catch (const std::exception& e)
{
@@ -136,12 +129,10 @@ template
bool runTest(ElementType& type,
std::function&,
- bool,
- const int)> func,
+ bool)> func,
const std::string& xml_string,
const std::string& element_name,
std::unordered_map& available_materials,
- int version,
const bool visual)
{
tinyxml2::XMLDocument xml_doc;
@@ -152,7 +143,7 @@ bool runTest(ElementType& type,
try
{
- type = func(element, available_materials, visual, version);
+ type = func(element, available_materials, visual);
}
catch (const std::exception& e)
{
diff --git a/tesseract_urdf/test/tesseract_urdf_cone_unit.cpp b/tesseract_urdf/test/tesseract_urdf_cone_unit.cpp
index 0cd399b9ec1..5f4e9ecd4f7 100644
--- a/tesseract_urdf/test/tesseract_urdf_cone_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_cone_unit.cpp
@@ -11,70 +11,79 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
TEST(TesseractURDFUnit, parse_cone) // NOLINT
{
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_TRUE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_TRUE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
EXPECT_NEAR(geom->getRadius(), 1, 1e-8);
EXPECT_NEAR(geom->getLength(), 2, 1e-8);
}
{ // https://github.com/ros-industrial-consortium/tesseract_ros/issues/67
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_TRUE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_TRUE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
EXPECT_NEAR(geom->getRadius(), 0.25, 1e-8);
EXPECT_NEAR(geom->getLength(), 0.5, 1e-8);
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
}
// TODO: I would expect this to fail but tinyxml2 still parses it so need to create an issue.
// {
- // std::string str = R"()";
+ // std::string str = R"()";
// tesseract_geometry::Cone::Ptr geom;
- // auto status = runTest(geom, str, "cone");
+ // auto status = runTest(geom, str, tesseract_urdf::CONE_ELEMENT_NAME);
// EXPECT_FALSE(*status);
// EXPECT_FALSE(status->message().empty());
// }
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
}
{
- std::string str = R"()";
+ std::string str = R"()";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
}
{
- std::string str = "";
+ std::string str = "";
tesseract_geometry::Cone::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCone, str, "cone", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCone, str, tesseract_urdf::CONE_ELEMENT_NAME));
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_convex_mesh_unit.cpp b/tesseract_urdf/test/tesseract_urdf_convex_mesh_unit.cpp
index 0f59d8d60e4..093eb199277 100644
--- a/tesseract_urdf/test/tesseract_urdf_convex_mesh_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_convex_mesh_unit.cpp
@@ -25,10 +25,14 @@ TEST(TesseractURDFUnit, parse_convex_mesh) // NOLINT
tesseract_common::GeneralResourceLocator resource_locator;
{
std::string str =
- R"()";
+ R"()";
std::vector geom;
- EXPECT_TRUE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_TRUE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.size() == 1);
EXPECT_TRUE(geom[0]->getFaceCount() == 6);
EXPECT_TRUE(geom[0]->getVertexCount() == 8);
@@ -39,10 +43,10 @@ TEST(TesseractURDFUnit, parse_convex_mesh) // NOLINT
{
std::string str =
- R"()";
+ R"()";
std::vector geom;
EXPECT_TRUE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, true));
+ geom, &tesseract_urdf::parseConvexMesh, str, tesseract_urdf::CONVEX_MESH_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(geom.size() == 1);
EXPECT_TRUE(geom[0]->getFaceCount() == 12);
EXPECT_TRUE(geom[0]->getVertexCount() == 8);
@@ -53,10 +57,14 @@ TEST(TesseractURDFUnit, parse_convex_mesh) // NOLINT
{
std::string str =
- R"()";
+ R"()";
std::vector geom;
- EXPECT_TRUE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_TRUE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.size() == 1);
EXPECT_TRUE(geom[0]->getFaceCount() >= 6); // Because we are converting due to numerical variance you could end up
// with additional faces.
@@ -65,18 +73,26 @@ TEST(TesseractURDFUnit, parse_convex_mesh) // NOLINT
{
std::string str =
- R"()";
+ R"()";
std::vector geom;
- EXPECT_TRUE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_TRUE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.size() == 2);
}
{
- std::string str = R"()";
+ std::string str = R"()";
std::vector geom;
- EXPECT_TRUE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_TRUE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.size() == 1);
EXPECT_TRUE(geom[0]->getFaceCount() == 6);
EXPECT_TRUE(geom[0]->getVertexCount() == 8);
@@ -86,90 +102,142 @@ TEST(TesseractURDFUnit, parse_convex_mesh) // NOLINT
}
{
- std::string str = R"()";
+ std::string str =
+ R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str =
+ R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str =
+ R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str =
+ R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str =
+ R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str =
+ R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str = R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str =
+ R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str =
+ R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = R"()";
+ std::string str = R"()";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
{
- std::string str = "";
+ std::string str = "";
std::vector geom;
- EXPECT_FALSE(runTest>(
- geom, &tesseract_urdf::parseConvexMesh, str, "convex_mesh", resource_locator, 2, false));
+ EXPECT_FALSE(runTest>(geom,
+ &tesseract_urdf::parseConvexMesh,
+ str,
+ tesseract_urdf::CONVEX_MESH_ELEMENT_NAME,
+ resource_locator,
+ false));
EXPECT_TRUE(geom.empty());
}
}
@@ -188,7 +256,7 @@ TEST(TesseractURDFUnit, write_convex_mesh) // NOLINT
EXPECT_EQ(0,
writeTest(
convex_mesh, &tesseract_urdf::writeConvexMesh, text, getTempPkgPath(), std::string("convex0.ply")));
- EXPECT_EQ(text, R"()");
+ EXPECT_EQ(text, R"()");
}
{
diff --git a/tesseract_urdf/test/tesseract_urdf_cylinder_unit.cpp b/tesseract_urdf/test/tesseract_urdf_cylinder_unit.cpp
index 8f0df432950..5f8899d3fd2 100644
--- a/tesseract_urdf/test/tesseract_urdf_cylinder_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_cylinder_unit.cpp
@@ -13,7 +13,8 @@ TEST(TesseractURDFUnit, parse_cylinder) // NOLINT
{
std::string str = R"()";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_TRUE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_TRUE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
EXPECT_NEAR(geom->getRadius(), 1, 1e-8);
EXPECT_NEAR(geom->getLength(), 2, 1e-8);
}
@@ -21,7 +22,8 @@ TEST(TesseractURDFUnit, parse_cylinder) // NOLINT
{ // https://github.com/ros-industrial-consortium/tesseract_ros/issues/67
std::string str = R"()";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_TRUE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_TRUE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
EXPECT_NEAR(geom->getRadius(), 0.25, 1e-8);
EXPECT_NEAR(geom->getLength(), 0.5, 1e-8);
}
@@ -29,32 +31,36 @@ TEST(TesseractURDFUnit, parse_cylinder) // NOLINT
{
std::string str = R"()";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
}
// TODO: I would expect this to fail but tinyxml2 still parses it so need to create an issue.
// {
// std::string str = R"()";
// tesseract_geometry::Cylinder::Ptr geom;
- // auto status = runTest(geom, str, "cylinder", 2);
+ // auto status = runTest(geom, str, tesseract_urdf::CYLINDER_ELEMENT_NAME);
// EXPECT_FALSE(*status);
// EXPECT_FALSE(status->message().empty());
// }
@@ -62,19 +68,22 @@ TEST(TesseractURDFUnit, parse_cylinder) // NOLINT
{
std::string str = R"()";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
}
{
std::string str = "";
tesseract_geometry::Cylinder::Ptr geom;
- EXPECT_FALSE(runTest(geom, &tesseract_urdf::parseCylinder, str, "cylinder", 2));
+ EXPECT_FALSE(runTest(
+ geom, &tesseract_urdf::parseCylinder, str, tesseract_urdf::CYLINDER_ELEMENT_NAME));
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_dynamics_unit.cpp b/tesseract_urdf/test/tesseract_urdf_dynamics_unit.cpp
index d3ee8c2b309..23e118d1662 100644
--- a/tesseract_urdf/test/tesseract_urdf_dynamics_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_dynamics_unit.cpp
@@ -13,8 +13,8 @@ TEST(TesseractURDFUnit, parse_dynamics) // NOLINT
{
std::string str = R"()";
tesseract_scene_graph::JointDynamics::Ptr elem;
- EXPECT_TRUE(
- runTest(elem, &tesseract_urdf::parseDynamics, str, "dynamics", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseDynamics, str, tesseract_urdf::DYNAMICS_ELEMENT_NAME));
EXPECT_NEAR(elem->damping, 1, 1e-8);
EXPECT_NEAR(elem->friction, 2, 1e-8);
}
@@ -22,8 +22,8 @@ TEST(TesseractURDFUnit, parse_dynamics) // NOLINT
{
std::string str = R"()";
tesseract_scene_graph::JointDynamics::Ptr elem;
- EXPECT_TRUE(
- runTest(elem, &tesseract_urdf::parseDynamics, str, "dynamics", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseDynamics, str, tesseract_urdf::DYNAMICS_ELEMENT_NAME));
EXPECT_NEAR(elem->damping, 1, 1e-8);
EXPECT_NEAR(elem->friction, 0, 1e-8);
}
@@ -31,8 +31,8 @@ TEST(TesseractURDFUnit, parse_dynamics) // NOLINT
{
std::string str = R"()";
tesseract_scene_graph::JointDynamics::Ptr elem;
- EXPECT_TRUE(
- runTest(elem, &tesseract_urdf::parseDynamics, str, "dynamics", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseDynamics, str, tesseract_urdf::DYNAMICS_ELEMENT_NAME));
EXPECT_NEAR(elem->damping, 0, 1e-8);
EXPECT_NEAR(elem->friction, 2, 1e-8);
}
@@ -40,22 +40,22 @@ TEST(TesseractURDFUnit, parse_dynamics) // NOLINT
{
std::string str = R"()";
tesseract_scene_graph::JointDynamics::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseDynamics, str, "dynamics", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseDynamics, str, tesseract_urdf::DYNAMICS_ELEMENT_NAME));
}
{
std::string str = R"()";
tesseract_scene_graph::JointDynamics::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseDynamics, str, "dynamics", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseDynamics, str, tesseract_urdf::DYNAMICS_ELEMENT_NAME));
}
{
std::string str = "";
tesseract_scene_graph::JointDynamics::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseDynamics, str, "dynamics", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseDynamics, str, tesseract_urdf::DYNAMICS_ELEMENT_NAME));
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_extra_delimeters_unit.cpp b/tesseract_urdf/test/tesseract_urdf_extra_delimeters_unit.cpp
index b00baea2ba0..f112560cc33 100644
--- a/tesseract_urdf/test/tesseract_urdf_extra_delimeters_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_extra_delimeters_unit.cpp
@@ -12,7 +12,7 @@ TEST(TesseractURDFUnit, parse_extra_delimeters) // NOLINT
{
std::string str = R"()";
Eigen::Isometry3d origin;
- EXPECT_TRUE(runTest(origin, &tesseract_urdf::parseOrigin, str, "origin", 2));
+ EXPECT_TRUE(runTest(origin, &tesseract_urdf::parseOrigin, str, "origin"));
EXPECT_TRUE(origin.translation().isApprox(Eigen::Vector3d(0, 2.5, 0), 1e-8));
EXPECT_TRUE(origin.matrix().col(0).head(3).isApprox(Eigen::Vector3d(1, 0, 0), 1e-8));
EXPECT_TRUE(origin.matrix().col(1).head(3).isApprox(Eigen::Vector3d(0, -1, 0), 1e-8));
diff --git a/tesseract_urdf/test/tesseract_urdf_geometry_unit.cpp b/tesseract_urdf/test/tesseract_urdf_geometry_unit.cpp
index e4ff692031e..1020940ec16 100644
--- a/tesseract_urdf/test/tesseract_urdf_geometry_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_geometry_unit.cpp
@@ -19,7 +19,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::BOX);
}
@@ -29,7 +29,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::SPHERE);
}
@@ -39,49 +39,49 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::CYLINDER);
}
{
std::string str = R"(
-
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::CONE);
}
{
std::string str = R"(
-
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::CAPSULE);
}
{
std::string str = R"(
-
-
-
+
+
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::OCTREE);
}
{
std::string str = R"(
-
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::CONVEX_MESH);
}
@@ -91,17 +91,17 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::MESH);
}
{
std::string str = R"(
-
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_TRUE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::SDF_MESH);
}
@@ -111,7 +111,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
@@ -120,7 +120,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
@@ -130,7 +130,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
@@ -140,7 +140,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
@@ -150,49 +150,49 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
{
std::string str = R"(
-
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
{
std::string str = R"(
-
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
{
std::string str = R"(
-
-
-
+
+
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
{
std::string str = R"(
-
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
@@ -202,17 +202,17 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
{
std::string str = R"(
-
+
)";
tesseract_geometry::Geometry::Ptr elem;
EXPECT_FALSE(runTest(
- elem, &tesseract_urdf::parseGeometry, str, "geometry", resource_locator, 2, true));
+ elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true));
EXPECT_TRUE(elem == nullptr);
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_inertial_unit.cpp b/tesseract_urdf/test/tesseract_urdf_inertial_unit.cpp
index a1e0ce06c4b..58be9f26d38 100644
--- a/tesseract_urdf/test/tesseract_urdf_inertial_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_inertial_unit.cpp
@@ -16,8 +16,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_TRUE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
EXPECT_NEAR(elem->mass, 1, 1e-8);
EXPECT_NEAR(elem->ixx, 1, 1e-8);
EXPECT_NEAR(elem->ixy, 2, 1e-8);
@@ -33,8 +33,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_TRUE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
EXPECT_NEAR(elem->mass, 1, 1e-8);
EXPECT_NEAR(elem->ixx, 1, 1e-8);
EXPECT_NEAR(elem->ixy, 2, 1e-8);
@@ -51,8 +51,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -60,8 +60,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -69,8 +69,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -79,8 +79,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -89,8 +89,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -99,8 +99,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -109,8 +109,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -119,8 +119,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -129,8 +129,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -139,8 +139,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -149,8 +149,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -159,8 +159,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -169,8 +169,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -179,8 +179,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -189,8 +189,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -199,8 +199,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -209,8 +209,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
{
@@ -219,8 +219,8 @@ TEST(TesseractURDFUnit, parse_inertial) // NOLINT
)";
tesseract_scene_graph::Inertial::Ptr elem;
- EXPECT_FALSE(
- runTest(elem, &tesseract_urdf::parseInertial, str, "inertial", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseInertial, str, tesseract_urdf::INERTIAL_ELEMENT_NAME));
}
}
diff --git a/tesseract_urdf/test/tesseract_urdf_joint_unit.cpp b/tesseract_urdf/test/tesseract_urdf_joint_unit.cpp
index 82fdb39447a..62668d72312 100644
--- a/tesseract_urdf/test/tesseract_urdf_joint_unit.cpp
+++ b/tesseract_urdf/test/tesseract_urdf_joint_unit.cpp
@@ -22,7 +22,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::FLOATING);
EXPECT_FALSE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -48,7 +49,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::REVOLUTE);
EXPECT_FALSE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -70,7 +72,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::REVOLUTE);
EXPECT_TRUE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -92,7 +95,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::CONTINUOUS);
EXPECT_TRUE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -113,7 +117,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::CONTINUOUS);
EXPECT_TRUE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -135,7 +140,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::FIXED);
EXPECT_TRUE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -157,7 +163,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::PRISMATIC);
EXPECT_TRUE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -179,7 +186,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::REVOLUTE);
EXPECT_TRUE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -201,7 +209,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_TRUE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_TRUE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
EXPECT_TRUE(elem->getName() == "my_joint");
EXPECT_TRUE(elem->type == tesseract_scene_graph::JointType::PLANAR);
EXPECT_TRUE(elem->parent_to_joint_origin_transform.isApprox(Eigen::Isometry3d::Identity(), 1e-8));
@@ -221,7 +230,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_FALSE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
}
{
@@ -230,7 +240,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_FALSE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
}
{
@@ -238,7 +249,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_FALSE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
}
{
@@ -246,7 +258,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_FALSE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_FALSE(runTest(
+ elem, &tesseract_urdf::parseJoint, str, tesseract_urdf::JOINT_ELEMENT_NAME));
}
{
@@ -257,7 +270,8 @@ TEST(TesseractURDFUnit, parse_joint) // NOLINT
)";
tesseract_scene_graph::Joint::Ptr elem;
- EXPECT_FALSE(runTest(elem, &tesseract_urdf::parseJoint, str, "joint", 2));
+ EXPECT_FALSE(runTest