diff --git a/tesseract_collision/hpp_fcl/include/tesseract_collision/hpp_fcl/hpp_fcl_factories.h b/tesseract_collision/hpp_fcl/include/tesseract_collision/hpp_fcl/hpp_fcl_factories.h index 992ce82f93a..d2f91f2b462 100644 --- a/tesseract_collision/hpp_fcl/include/tesseract_collision/hpp_fcl/hpp_fcl_factories.h +++ b/tesseract_collision/hpp_fcl/include/tesseract_collision/hpp_fcl/hpp_fcl_factories.h @@ -33,7 +33,8 @@ namespace tesseract_collision::tesseract_collision_hpp_fcl class HPP_FCLDiscreteBVHManagerFactory : public DiscreteContactManagerFactory { public: - DiscreteContactManager::UPtr create(const std::string& name, const YAML::Node& config) const override final; + std::unique_ptr create(const std::string& name, + const YAML::Node& config) const override final; }; TESSERACT_PLUGIN_ANCHOR_DECL(HPP_FCLFactoriesAnchor) diff --git a/tesseract_collision/hpp_fcl/src/hpp_fcl_factories.cpp b/tesseract_collision/hpp_fcl/src/hpp_fcl_factories.cpp index 1bff078c507..b0534537d8f 100644 --- a/tesseract_collision/hpp_fcl/src/hpp_fcl_factories.cpp +++ b/tesseract_collision/hpp_fcl/src/hpp_fcl_factories.cpp @@ -26,11 +26,12 @@ #include #include +#include namespace tesseract_collision::tesseract_collision_hpp_fcl { -DiscreteContactManager::UPtr HPP_FCLDiscreteBVHManagerFactory::create(const std::string& name, - const YAML::Node& /*config*/) const +std::unique_ptr +HPP_FCLDiscreteBVHManagerFactory::create(const std::string& name, const YAML::Node& /*config*/) const { return std::make_unique(name); } @@ -42,4 +43,4 @@ TESSERACT_PLUGIN_ANCHOR_IMPL(HPP_FCLFactoriesAnchor) // LCOV_EXCL_LINE // NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) TESSERACT_ADD_DISCRETE_MANAGER_PLUGIN( tesseract_collision::tesseract_collision_hpp_fcl::HPP_FCLDiscreteBVHManagerFactory, - HPP_FCLDiscreteBVHManagerFactory); + HPP_FCLDiscreteBVHManagerFactory) diff --git a/tesseract_collision/hpp_fcl/src/hpp_fcl_utils.cpp b/tesseract_collision/hpp_fcl/src/hpp_fcl_utils.cpp index 2dbeb73342f..5234a0ebc56 100644 --- a/tesseract_collision/hpp_fcl/src/hpp_fcl_utils.cpp +++ b/tesseract_collision/hpp_fcl/src/hpp_fcl_utils.cpp @@ -149,7 +149,7 @@ CollisionGeometryPtr createShapePrimitive(const tesseract_geometry::Octree::Cons { switch (geom->getSubType()) { - case tesseract_geometry::Octree::SubType::BOX: + case tesseract_geometry::OctreeSubType::BOX: { return CollisionGeometryPtr(new hpp::fcl::OcTree(geom->getOctree())); }