From 43ccf6d65b7dfdabfcb839711468e99bbe7bd315 Mon Sep 17 00:00:00 2001 From: Michael Ripperger Date: Sat, 11 Jan 2025 21:42:40 -0600 Subject: [PATCH] Updated unit tests --- tesseract_urdf/test/CMakeLists.txt | 1 - .../test/tesseract_urdf_collision_unit.cpp | 15 +- .../test/tesseract_urdf_convex_mesh_unit.cpp | 289 ------------------ .../test/tesseract_urdf_geometry_unit.cpp | 80 ++--- .../test/tesseract_urdf_link_unit.cpp | 110 ++----- .../tesseract_urdf_mesh_material_unit.cpp | 26 +- .../test/tesseract_urdf_mesh_unit.cpp | 101 ++++-- 7 files changed, 160 insertions(+), 462 deletions(-) delete mode 100644 tesseract_urdf/test/tesseract_urdf_convex_mesh_unit.cpp diff --git a/tesseract_urdf/test/CMakeLists.txt b/tesseract_urdf/test/CMakeLists.txt index efce108c906..7f64f1396ec 100644 --- a/tesseract_urdf/test/CMakeLists.txt +++ b/tesseract_urdf/test/CMakeLists.txt @@ -8,7 +8,6 @@ add_executable( tesseract_urdf_capsule_unit.cpp tesseract_urdf_collision_unit.cpp tesseract_urdf_cone_unit.cpp - tesseract_urdf_convex_mesh_unit.cpp tesseract_urdf_cylinder_unit.cpp tesseract_urdf_dynamics_unit.cpp tesseract_urdf_extra_delimeters_unit.cpp diff --git a/tesseract_urdf/test/tesseract_urdf_collision_unit.cpp b/tesseract_urdf/test/tesseract_urdf_collision_unit.cpp index fc1087c2cf4..374e865fc6e 100644 --- a/tesseract_urdf/test/tesseract_urdf_collision_unit.cpp +++ b/tesseract_urdf/test/tesseract_urdf_collision_unit.cpp @@ -13,6 +13,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP TEST(TesseractURDFUnit, parse_collision) // NOLINT { tesseract_common::GeneralResourceLocator resource_locator; + const bool global_make_convex = false; + const auto parse_collision_fn = + std::bind(&tesseract_urdf::parseCollision, std::placeholders::_1, std::placeholders::_2, global_make_convex); { std::string str = R"( @@ -23,7 +26,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT )"; tesseract_scene_graph::Collision::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); + elem, parse_collision_fn, 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 +39,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT )"; tesseract_scene_graph::Collision::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); + elem, parse_collision_fn, 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 +52,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT )"; tesseract_scene_graph::Collision::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); + elem, parse_collision_fn, 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 +68,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT )"; tesseract_scene_graph::Collision::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); + elem, parse_collision_fn, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); EXPECT_TRUE(elem == nullptr); } @@ -77,7 +80,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT )"; tesseract_scene_graph::Collision::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); + elem, parse_collision_fn, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); EXPECT_TRUE(elem == nullptr); } @@ -86,7 +89,7 @@ TEST(TesseractURDFUnit, parse_collision) // NOLINT )"; tesseract_scene_graph::Collision::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseCollision, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); + elem, parse_collision_fn, str, tesseract_urdf::COLLISION_ELEMENT_NAME, resource_locator)); EXPECT_TRUE(elem == nullptr); } } diff --git a/tesseract_urdf/test/tesseract_urdf_convex_mesh_unit.cpp b/tesseract_urdf/test/tesseract_urdf_convex_mesh_unit.cpp deleted file mode 100644 index 093eb199277..00000000000 --- a/tesseract_urdf/test/tesseract_urdf_convex_mesh_unit.cpp +++ /dev/null @@ -1,289 +0,0 @@ -#include -TESSERACT_COMMON_IGNORE_WARNINGS_PUSH -#include -#include -TESSERACT_COMMON_IGNORE_WARNINGS_POP - -#include -#include -#include -#include "tesseract_urdf_common_unit.h" - -static std::string getTempPkgPath() -{ - std::string tmp = tesseract_common::getTempPath(); - std::string tmppkg = tmp + "tmppkg"; - if (!tesseract_common::fs::is_directory(tmppkg) || !tesseract_common::fs::exists(tmppkg)) - { - tesseract_common::fs::create_directory(tmppkg); - } - return tmppkg; -} - -TEST(TesseractURDFUnit, parse_convex_mesh) // NOLINT -{ - tesseract_common::GeneralResourceLocator resource_locator; - { - std::string str = - R"()"; - std::vector geom; - 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); - EXPECT_NEAR(geom[0]->getScale()[0], 1, 1e-5); - EXPECT_NEAR(geom[0]->getScale()[1], 2, 1e-5); - EXPECT_NEAR(geom[0]->getScale()[2], 1, 1e-5); - } - - { - std::string str = - R"()"; - std::vector geom; - EXPECT_TRUE(runTest>( - 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); - EXPECT_NEAR(geom[0]->getScale()[0], 1, 1e-5); - EXPECT_NEAR(geom[0]->getScale()[1], 2, 1e-5); - EXPECT_NEAR(geom[0]->getScale()[2], 1, 1e-5); - } - - { - std::string str = - R"()"; - std::vector geom; - 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. - EXPECT_TRUE(geom[0]->getVertexCount() == 8); - } - - { - std::string str = - R"()"; - std::vector geom; - 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::vector geom; - 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); - EXPECT_NEAR(geom[0]->getScale()[0], 1, 1e-5); - EXPECT_NEAR(geom[0]->getScale()[1], 1, 1e-5); - EXPECT_NEAR(geom[0]->getScale()[2], 1, 1e-5); - } - - { - std::string str = - R"()"; - std::vector geom; - 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::vector geom; - 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::vector geom; - 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::vector geom; - 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::vector geom; - 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::vector geom; - 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::vector geom; - 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::vector geom; - 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::vector geom; - 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::vector geom; - 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::vector geom; - EXPECT_FALSE(runTest>(geom, - &tesseract_urdf::parseConvexMesh, - str, - tesseract_urdf::CONVEX_MESH_ELEMENT_NAME, - resource_locator, - false)); - EXPECT_TRUE(geom.empty()); - } -} - -TEST(TesseractURDFUnit, write_convex_mesh) // NOLINT -{ - { - tesseract_common::VectorVector3d vertices = { Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d(1, 0, 0), - Eigen::Vector3d(0, 1, 0) }; - Eigen::VectorXi indices(4); - indices << 3, 0, 1, 2; - tesseract_geometry::ConvexMesh::Ptr convex_mesh = std::make_shared( - std::make_shared(vertices), std::make_shared(indices)); - std::string text; - EXPECT_EQ(0, - writeTest( - convex_mesh, &tesseract_urdf::writeConvexMesh, text, getTempPkgPath(), std::string("convex0.ply"))); - EXPECT_EQ(text, R"()"); - } - - { - tesseract_common::VectorVector3d vertices = { Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d(1, 0, 0), - Eigen::Vector3d(0, 1, 0) }; - Eigen::VectorXi indices(4); - indices << 3, 0, 1, 2; - tesseract_geometry::ConvexMesh::Ptr convex_mesh = std::make_shared( - std::make_shared(vertices), std::make_shared(indices)); - std::string text; - EXPECT_EQ( - 1, - writeTest( - convex_mesh, &tesseract_urdf::writeConvexMesh, text, tesseract_common::getTempPath(), std::string(""))); - EXPECT_EQ(text, ""); - } - - { - tesseract_geometry::ConvexMesh::Ptr convex_mesh = nullptr; - std::string text; - EXPECT_EQ(1, - writeTest(convex_mesh, - &tesseract_urdf::writeConvexMesh, - text, - tesseract_common::getTempPath(), - std::string("convex1.ply"))); - EXPECT_EQ(text, ""); - } -} diff --git a/tesseract_urdf/test/tesseract_urdf_geometry_unit.cpp b/tesseract_urdf/test/tesseract_urdf_geometry_unit.cpp index 1020940ec16..a40fe8d6c31 100644 --- a/tesseract_urdf/test/tesseract_urdf_geometry_unit.cpp +++ b/tesseract_urdf/test/tesseract_urdf_geometry_unit.cpp @@ -12,6 +12,13 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP TEST(TesseractURDFUnit, parse_geometry) // NOLINT { + const bool global_make_convex = false; + const auto parse_geometry_fn = std::bind(&tesseract_urdf::parseGeometry, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3, + global_make_convex); + tesseract_common::GeneralResourceLocator resource_locator; { std::string str = R"( @@ -19,7 +26,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::BOX); } @@ -29,7 +36,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::SPHERE); } @@ -39,7 +46,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::CYLINDER); } @@ -49,7 +56,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::CONE); } @@ -59,7 +66,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::CAPSULE); } @@ -71,27 +78,17 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, 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, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); - EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::CONVEX_MESH); - } - { std::string str = R"( )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::MESH); } @@ -101,7 +98,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_TRUE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem->getType() == tesseract_geometry::GeometryType::SDF_MESH); } @@ -111,7 +108,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -120,7 +117,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -130,7 +127,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -140,7 +137,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -150,7 +147,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -160,7 +157,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -170,7 +167,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -182,17 +179,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - 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, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -202,7 +189,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } @@ -212,7 +199,7 @@ TEST(TesseractURDFUnit, parse_geometry) // NOLINT )"; tesseract_geometry::Geometry::Ptr elem; EXPECT_FALSE(runTest( - elem, &tesseract_urdf::parseGeometry, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); + elem, parse_geometry_fn, str, tesseract_urdf::GEOMETRY_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(elem == nullptr); } } @@ -303,23 +290,6 @@ TEST(TesseractURDFUnit, write_geometry) // NOLINT EXPECT_NE(text, ""); } - { // convex_mesh - tesseract_common::VectorVector3d vertices = { Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d(1, 0, 0), - Eigen::Vector3d(0, 1, 0) }; - Eigen::VectorXi indices(4); - indices << 3, 0, 1, 2; - tesseract_geometry::Geometry::Ptr geometry = std::make_shared( - std::make_shared(vertices), std::make_shared(indices)); - - std::string text; - EXPECT_EQ( - 0, - writeTest( - geometry, &tesseract_urdf::writeGeometry, text, tesseract_common::getTempPath(), std::string("geom1"))); - EXPECT_NE(text, ""); - } - { // sdf_mesh tesseract_common::VectorVector3d vertices = { Eigen::Vector3d(0, 0, 0), Eigen::Vector3d(1, 0, 0), diff --git a/tesseract_urdf/test/tesseract_urdf_link_unit.cpp b/tesseract_urdf/test/tesseract_urdf_link_unit.cpp index 8ca6a71c3da..33b54ee4cbe 100644 --- a/tesseract_urdf/test/tesseract_urdf_link_unit.cpp +++ b/tesseract_urdf/test/tesseract_urdf_link_unit.cpp @@ -13,6 +13,12 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP TEST(TesseractURDFUnit, parse_link) // NOLINT { tesseract_common::GeneralResourceLocator resource_locator; + const bool global_make_convex = false; + const auto parse_link_fn = std::bind(&tesseract_urdf::parseLink, + std::placeholders::_1, + std::placeholders::_2, + global_make_convex, + std::placeholders::_3); { std::unordered_map empty_available_materials; @@ -39,12 +45,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial != nullptr); EXPECT_TRUE(elem->visual.size() == 1); @@ -92,12 +94,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial != nullptr); EXPECT_TRUE(elem->visual.size() == 2); @@ -125,12 +123,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial == nullptr); EXPECT_TRUE(elem->visual.size() == 1); @@ -171,12 +165,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial == nullptr); EXPECT_TRUE(elem->visual.size() == 2); @@ -198,12 +188,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial == nullptr); EXPECT_TRUE(elem->visual.size() == 1); @@ -232,12 +218,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial == nullptr); EXPECT_TRUE(elem->visual.size() == 2); @@ -256,12 +238,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial == nullptr); EXPECT_TRUE(elem->visual.empty()); @@ -286,12 +264,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial == nullptr); EXPECT_TRUE(elem->visual.empty()); @@ -303,12 +277,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT std::unordered_map empty_available_materials; std::string str = R"()"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_TRUE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_TRUE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); EXPECT_TRUE(elem->getName() == "my_link"); EXPECT_TRUE(elem->inertial == nullptr); EXPECT_TRUE(elem->visual.empty()); @@ -329,12 +299,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_FALSE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_FALSE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); } { @@ -351,12 +317,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_FALSE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_FALSE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); } { @@ -374,12 +336,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_FALSE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_FALSE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); } { @@ -393,12 +351,8 @@ TEST(TesseractURDFUnit, parse_link) // NOLINT )"; tesseract_scene_graph::Link::Ptr elem; - EXPECT_FALSE(runTest(elem, - &tesseract_urdf::parseLink, - str, - tesseract_urdf::LINK_ELEMENT_NAME, - resource_locator, - empty_available_materials)); + EXPECT_FALSE(runTest( + elem, parse_link_fn, str, tesseract_urdf::LINK_ELEMENT_NAME, resource_locator, empty_available_materials)); } } diff --git a/tesseract_urdf/test/tesseract_urdf_mesh_material_unit.cpp b/tesseract_urdf/test/tesseract_urdf_mesh_material_unit.cpp index bb3165d6e5a..286e45c0400 100644 --- a/tesseract_urdf/test/tesseract_urdf_mesh_material_unit.cpp +++ b/tesseract_urdf/test/tesseract_urdf_mesh_material_unit.cpp @@ -13,11 +13,18 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP TEST(TesseractURDFUnit, parse_mesh_material_dae) // NOLINT { tesseract_common::GeneralResourceLocator resource_locator; + const bool global_make_convex = false; + const auto parse_mesh_fn = std::bind(&tesseract_urdf::parseMesh, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3, + global_make_convex); + { std::string str = R"()"; - std::vector meshes; - EXPECT_TRUE(runTest>( - meshes, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector meshes; + EXPECT_TRUE(runTest>( + meshes, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(meshes.size() == 4); auto& mesh0 = meshes[1]; auto& mesh1 = meshes[2]; @@ -87,11 +94,18 @@ TEST(TesseractURDFUnit, parse_mesh_material_dae) // NOLINT TEST(TesseractURDFUnit, parse_mesh_material_gltf2) // NOLINT { tesseract_common::GeneralResourceLocator resource_locator; + const bool global_make_convex = false; + const auto parse_mesh_fn = std::bind(&tesseract_urdf::parseMesh, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3, + global_make_convex); + { std::string str = R"()"; - std::vector meshes; - EXPECT_TRUE(runTest>( - meshes, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector meshes; + EXPECT_TRUE(runTest>( + meshes, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(meshes.size() == 4); auto& mesh0 = meshes[0]; auto& mesh1 = meshes[1]; diff --git a/tesseract_urdf/test/tesseract_urdf_mesh_unit.cpp b/tesseract_urdf/test/tesseract_urdf_mesh_unit.cpp index 866efac7579..90632cc4d4e 100644 --- a/tesseract_urdf/test/tesseract_urdf_mesh_unit.cpp +++ b/tesseract_urdf/test/tesseract_urdf_mesh_unit.cpp @@ -23,12 +23,19 @@ static std::string getTempPkgPath() TEST(TesseractURDFUnit, parse_mesh) // NOLINT { tesseract_common::GeneralResourceLocator resource_locator; + const bool global_make_convex = false; + const auto parse_mesh_fn = std::bind(&tesseract_urdf::parseMesh, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3, + global_make_convex); + { std::string str = R"()"; - std::vector geom; - EXPECT_TRUE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_TRUE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.size() == 1); EXPECT_TRUE(geom[0]->getFaceCount() == 80); EXPECT_TRUE(geom[0]->getVertexCount() == 240); @@ -39,9 +46,24 @@ TEST(TesseractURDFUnit, parse_mesh) // NOLINT { std::string str = R"()"; - std::vector geom; - EXPECT_TRUE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_TRUE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + EXPECT_TRUE(geom.size() == 1); + EXPECT_TRUE(geom[0]->getFaceCount() == 80); + EXPECT_TRUE(geom[0]->getVertexCount() == 240); + EXPECT_NEAR(geom[0]->getScale()[0], 1, 1e-5); + EXPECT_NEAR(geom[0]->getScale()[1], 1, 1e-5); + EXPECT_NEAR(geom[0]->getScale()[2], 1, 1e-5); + } + + // Make convex override false (correct) + { + std::string str = + R"()"; + std::vector geom; + EXPECT_TRUE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.size() == 1); EXPECT_TRUE(geom[0]->getFaceCount() == 80); EXPECT_TRUE(geom[0]->getVertexCount() == 240); @@ -50,59 +72,84 @@ TEST(TesseractURDFUnit, parse_mesh) // NOLINT EXPECT_NEAR(geom[0]->getScale()[2], 1, 1e-5); } + // Make convex override true (correct) + { + std::string str = + R"()"; + std::vector geom; + EXPECT_TRUE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + EXPECT_TRUE(geom.size() == 1); + // EXPECT_TRUE(geom[0]->getFaceCount() == 80); + // EXPECT_TRUE(geom[0]->getVertexCount() == 240); + EXPECT_NEAR(geom[0]->getScale()[0], 1, 1e-5); + EXPECT_NEAR(geom[0]->getScale()[1], 1, 1e-5); + EXPECT_NEAR(geom[0]->getScale()[2], 1, 1e-5); + } + + // Make convex (incorrect) + { + std::string str = + R"()"; + std::vector geom; + EXPECT_FALSE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + EXPECT_TRUE(geom.empty()); + } + { std::string str = R"()"; - std::vector geom; - EXPECT_FALSE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_FALSE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.empty()); } { std::string str = R"()"; - std::vector geom; - EXPECT_FALSE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_FALSE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.empty()); } { std::string str = R"()"; - std::vector geom; - EXPECT_FALSE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_FALSE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.empty()); } { std::string str = R"()"; - std::vector geom; - EXPECT_FALSE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_FALSE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.empty()); } { std::string str = R"()"; - std::vector geom; - EXPECT_FALSE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_FALSE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.empty()); } { std::string str = R"()"; - std::vector geom; - EXPECT_FALSE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_FALSE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.empty()); } { std::string str = ""; - std::vector geom; - EXPECT_FALSE(runTest>( - geom, &tesseract_urdf::parseMesh, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); + std::vector geom; + EXPECT_FALSE(runTest>( + geom, parse_mesh_fn, str, tesseract_urdf::MESH_ELEMENT_NAME, resource_locator, true)); EXPECT_TRUE(geom.empty()); } }