Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix Serialization and Remove TesseractSupportResourceLocator #1051

Merged
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
2 changes: 0 additions & 2 deletions tesseract_collision/examples/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
find_package(tesseract_support REQUIRED)
add_executable(${PROJECT_NAME}_box_box_example box_box_example.cpp)
target_link_libraries(
${PROJECT_NAME}_box_box_example
${PROJECT_NAME}_bullet
${PROJECT_NAME}_fcl
tesseract::tesseract_support
tesseract::tesseract_geometry
console_bridge::console_bridge
${Boost_LIBRARIES}
Expand Down
7 changes: 6 additions & 1 deletion tesseract_collision/examples/box_box_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/bullet/bullet_discrete_bvh_manager.h>
#include <tesseract_collision/bullet/convex_hull_utils.h>
#include <tesseract_geometry/impl/box.h>
#include <tesseract_common/resource_locator.h>

using namespace tesseract_collision;
using namespace tesseract_geometry;
Expand Down Expand Up @@ -57,11 +58,15 @@ int main(int /*argc*/, char** /*argv*/)

// documentation:start:4: Add convex hull
// Add second box to checker, but convert to convex hull mesh
tesseract_common::GeneralResourceLocator locator;
CollisionShapePtr second_box;

auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
loadSimplePlyFile(std::string(TESSERACT_SUPPORT_DIR) + "/meshes/box_2m.ply", *mesh_vertices, *mesh_faces, true);
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/box_2m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true);

auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
second_box = makeConvexMesh(*mesh);
Expand Down
2 changes: 0 additions & 2 deletions tesseract_collision/test/benchmarks/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
find_package(benchmark REQUIRED)
find_package(tesseract_support REQUIRED)
find_package(tesseract_scene_graph REQUIRED)

macro(add_benchmark benchmark_name benchmark_file)
Expand Down Expand Up @@ -43,7 +42,6 @@ target_link_libraries(
PRIVATE ${PROJECT_NAME}_bullet
${PROJECT_NAME}_fcl
tesseract::tesseract_geometry
tesseract::tesseract_support
${Boost_LIBRARIES}
${OCTOMAP_LIBRARIES}
${LIBFCL_LIBRARIES})
Expand Down
18 changes: 13 additions & 5 deletions tesseract_collision/test/benchmarks/collision_profile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/fcl/fcl_discrete_managers.h>

#include <tesseract_geometry/impl/sphere.h>

#include <tesseract_common/resource_locator.h>
static const std::size_t DIM = 10;

using namespace tesseract_collision;
Expand All @@ -31,8 +31,12 @@ void addCollisionObjects(DiscreteContactManager& checker, bool use_single_link,
{
auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
loadSimplePlyFile(
std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true);

tesseract_common::GeneralResourceLocator locator;
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true);

auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
sphere = makeConvexMesh(*mesh);
Expand Down Expand Up @@ -98,8 +102,12 @@ void addCollisionObjects(ContinuousContactManager& checker, bool use_single_link
{
auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
loadSimplePlyFile(
std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true);

tesseract_common::GeneralResourceLocator locator;
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true);

auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
sphere = makeConvexMesh(*mesh);
Expand Down
14 changes: 4 additions & 10 deletions tesseract_collision/test_suite/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,12 +1,7 @@
find_package(tesseract_support REQUIRED)
# Create test suite interface
add_library(${PROJECT_NAME}_test_suite INTERFACE)
target_link_libraries(
${PROJECT_NAME}_test_suite
INTERFACE Eigen3::Eigen
tesseract::tesseract_support
tesseract::tesseract_geometry
${PROJECT_NAME}_core)
target_link_libraries(${PROJECT_NAME}_test_suite INTERFACE Eigen3::Eigen tesseract::tesseract_geometry
${PROJECT_NAME}_core)
target_compile_options(${PROJECT_NAME}_test_suite INTERFACE ${TESSERACT_COMPILE_OPTIONS_PUBLIC})
target_compile_definitions(${PROJECT_NAME}_test_suite INTERFACE ${TESSERACT_COMPILE_DEFINITIONS})
target_cxx_version(${PROJECT_NAME}_test_suite INTERFACE VERSION ${TESSERACT_CXX_VERSION})
Expand All @@ -16,8 +11,7 @@ target_include_directories(${PROJECT_NAME}_test_suite INTERFACE "$<BUILD_INTERFA

# Create test suite benchmarks interface
add_library(${PROJECT_NAME}_test_suite_benchmarks INTERFACE)
target_link_libraries(${PROJECT_NAME}_test_suite_benchmarks INTERFACE Eigen3::Eigen tesseract::tesseract_support
tesseract::tesseract_geometry)
target_link_libraries(${PROJECT_NAME}_test_suite_benchmarks INTERFACE Eigen3::Eigen tesseract::tesseract_geometry)
target_compile_options(${PROJECT_NAME}_test_suite_benchmarks INTERFACE ${TESSERACT_COMPILE_OPTIONS_PUBLIC})
target_cxx_version(${PROJECT_NAME}_test_suite_benchmarks INTERFACE VERSION ${TESSERACT_CXX_VERSION})
target_clang_tidy(${PROJECT_NAME}_test_suite_benchmarks ENABLE ${TESSERACT_ENABLE_CLANG_TIDY})
Expand All @@ -38,7 +32,7 @@ configure_component(
COMPONENT test_suite
NAMESPACE tesseract
TARGETS ${PROJECT_NAME}_test_suite ${PROJECT_NAME}_test_suite_benchmarks
DEPENDENCIES tesseract_support "tesseract_collision COMPONENTS core")
DEPENDENCIES "tesseract_collision COMPONENTS core")

if(TESSERACT_PACKAGE)
cpack_component(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision
{
Expand All @@ -27,7 +28,12 @@ static void BM_LARGE_DATASET_MULTILINK(benchmark::State& state,

auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
loadSimplePlyFile(std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true);

tesseract_common::GeneralResourceLocator locator;
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true);

switch (type)
{
Expand Down Expand Up @@ -111,7 +117,12 @@ static void BM_LARGE_DATASET_SINGLELINK(benchmark::State& state,

auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
loadSimplePlyFile(std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true);

tesseract_common::GeneralResourceLocator locator;
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true);

switch (type)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand Down Expand Up @@ -54,8 +55,11 @@ inline void addCollisionObjects(DiscreteContactManager& checker, bool use_convex
auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
// TODO: Need to figure out why this test not pass of bullet when using the box_2m.ply mesh
EXPECT_GT(loadSimplePlyFile(
std::string(TESSERACT_SUPPORT_DIR) + "/meshes/box2_2m.ply", *mesh_vertices, *mesh_faces, true),
tesseract_common::GeneralResourceLocator locator;
EXPECT_GT(loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/box2_2m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true),
0);

auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand Down Expand Up @@ -52,9 +53,13 @@ inline void addCollisionObjects(DiscreteContactManager& checker, bool use_convex
{
auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
EXPECT_GT(loadSimplePlyFile(
std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true),
0);
tesseract_common::GeneralResourceLocator locator;
EXPECT_GT(
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true),
0);

auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
sphere = makeConvexMesh(*mesh);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/continuous_contact_manager.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand All @@ -20,7 +21,8 @@ inline void addCollisionObjects(T& checker)
/////////////////////////////////////////////////////////////////
// Add Octomap
/////////////////////////////////////////////////////////////////
std::string path = std::string(TESSERACT_SUPPORT_DIR) + "/meshes/box_2m.bt";
tesseract_common::GeneralResourceLocator locator;
std::string path = locator.locateResource("package://tesseract_support/meshes/box_2m.bt")->getFilePath();
auto ot = std::make_shared<octomap::OcTree>(path);
CollisionShapePtr dense_octomap =
std::make_shared<tesseract_geometry::Octree>(ot, tesseract_geometry::OctreeSubType::BOX);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand All @@ -23,9 +24,13 @@ inline void runTest(DiscreteContactManager& checker, bool use_convex_mesh = fals
{
auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
EXPECT_GT(loadSimplePlyFile(
std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true),
0);
tesseract_common::GeneralResourceLocator locator;
EXPECT_GT(
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true),
0);

auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
sphere = makeConvexMesh(*mesh);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand All @@ -18,8 +19,12 @@ inline void addCollisionObjects(DiscreteContactManager& checker)

auto vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto faces = std::make_shared<Eigen::VectorXi>();
tesseract_common::GeneralResourceLocator locator;
int num_faces =
loadSimplePlyFile(std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *vertices, *faces, true);
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*vertices,
*faces,
true);
EXPECT_GT(num_faces, 0);

sphere = std::make_shared<tesseract_geometry::Mesh>(vertices, faces);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand All @@ -22,9 +23,13 @@ inline void runTest(DiscreteContactManager& checker, bool use_convex_mesh = fals
{
auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
EXPECT_GT(loadSimplePlyFile(
std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true),
0);
tesseract_common::GeneralResourceLocator locator;
EXPECT_GT(
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true),
0);

auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
sphere = makeConvexMesh(*mesh);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand All @@ -21,7 +22,8 @@ inline void addCollisionObjects(DiscreteContactManager& checker)
/////////////////////////////////////////////////////////////////
// Add Octomap
/////////////////////////////////////////////////////////////////
std::string path = std::string(TESSERACT_SUPPORT_DIR) + "/meshes/box_2m.bt";
tesseract_common::GeneralResourceLocator locator;
std::string path = locator.locateResource("package://tesseract_support/meshes/box_2m.bt")->getFilePath();
auto ot = std::make_shared<octomap::OcTree>(path);
CollisionShapePtr dense_octomap =
std::make_shared<tesseract_geometry::Octree>(ot, tesseract_geometry::OctreeSubType::BOX);
Expand All @@ -39,7 +41,9 @@ inline void addCollisionObjects(DiscreteContactManager& checker)
// Add plane mesh to checker.
/////////////////////////////////////////////////////////////////
CollisionShapePtr sphere = tesseract_geometry::createMeshFromPath<tesseract_geometry::Mesh>(
std::string(TESSERACT_SUPPORT_DIR) + "/meshes/plane_4m.stl", Eigen::Vector3d(1, 1, 1), true)[0];
locator.locateResource("package://tesseract_support/meshes/plane_4m.stl")->getFilePath(),
Eigen::Vector3d(1, 1, 1),
true)[0];

Eigen::Isometry3d sphere_pose;
sphere_pose.setIdentity();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/continuous_contact_manager.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand All @@ -20,7 +21,8 @@ inline void addCollisionObjects(T& checker)
/////////////////////////////////////////////////////////////////
// Add Octomap
/////////////////////////////////////////////////////////////////
std::string path = std::string(TESSERACT_SUPPORT_DIR) + "/meshes/box_2m.bt";
tesseract_common::GeneralResourceLocator locator;
std::string path = locator.locateResource("package://tesseract_support/meshes/box_2m.bt")->getFilePath();
auto ot = std::make_shared<octomap::OcTree>(path);
CollisionShapePtr dense_octomap =
std::make_shared<tesseract_geometry::Octree>(ot, tesseract_geometry::OctreeSubType::SPHERE_OUTSIDE);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_geometry/geometries.h>
#include <tesseract_common/resource_locator.h>

namespace tesseract_collision::test_suite
{
Expand All @@ -22,7 +23,8 @@ inline void addCollisionObjects(DiscreteContactManager& checker, bool use_convex
/////////////////////////////////////////////////////////////////
// Add Octomap
/////////////////////////////////////////////////////////////////
std::string path = std::string(TESSERACT_SUPPORT_DIR) + "/meshes/blender_monkey.bt";
tesseract_common::GeneralResourceLocator locator;
std::string path = locator.locateResource("package://tesseract_support/meshes/blender_monkey.bt")->getFilePath();
auto ot = std::make_shared<octomap::OcTree>(path);
CollisionShapePtr dense_octomap =
std::make_shared<tesseract_geometry::Octree>(ot, tesseract_geometry::OctreeSubType::BOX);
Expand All @@ -46,9 +48,12 @@ inline void addCollisionObjects(DiscreteContactManager& checker, bool use_convex
{
auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
auto mesh_faces = std::make_shared<Eigen::VectorXi>();
EXPECT_GT(loadSimplePlyFile(
std::string(TESSERACT_SUPPORT_DIR) + "/meshes/sphere_p25m.ply", *mesh_vertices, *mesh_faces, true),
0);
EXPECT_GT(
loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
*mesh_vertices,
*mesh_faces,
true),
0);

auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
sphere = makeConvexMesh(*mesh);
Expand Down
Loading
Loading