Commit 4a79d753 authored by Joseph Mirabel's avatar Joseph Mirabel
Browse files

Reduce dependency to boost.

parent fc162433
......@@ -39,12 +39,11 @@
#ifndef HPP_FCL_BVH_MODEL_H
#define HPP_FCL_BVH_MODEL_H
#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/collision_object.h>
#include <hpp/fcl/BVH/BVH_internal.h>
#include <hpp/fcl/BV/BV_node.h>
#include <vector>
#include <boost/shared_ptr.hpp>
#include <boost/noncopyable.hpp>
namespace hpp
{
......@@ -82,7 +81,7 @@ public:
BVHBuildState build_state;
/// @brief Convex<Triangle> representation of this object
boost::shared_ptr< ConvexBase > convex;
shared_ptr< ConvexBase > convex;
/// @brief Model type described by the instance
BVHModelType getModelType() const
......@@ -275,10 +274,10 @@ class HPP_FCL_DLLAPI BVHModel : public BVHModelBase
public:
/// @brief Split rule to split one BV node into two children
boost::shared_ptr<BVSplitter<BV> > bv_splitter;
shared_ptr<BVSplitter<BV> > bv_splitter;
/// @brief Fitting rule to fit a BV node to a set of geometry primitives
boost::shared_ptr<BVFitter<BV> > bv_fitter;
shared_ptr<BVFitter<BV> > bv_fitter;
/// @brief Constructing an empty BVH
BVHModel();
......
......@@ -40,9 +40,9 @@
#define HPP_FCL_COLLISION_OBJECT_BASE_H
#include <hpp/fcl/deprecated.hh>
#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/BV/AABB.h>
#include <hpp/fcl/math/transform.h>
#include <boost/shared_ptr.hpp>
namespace hpp
{
......@@ -157,7 +157,7 @@ public:
class HPP_FCL_DLLAPI CollisionObject
{
public:
CollisionObject(const boost::shared_ptr<CollisionGeometry> &cgeom_) :
CollisionObject(const shared_ptr<CollisionGeometry> &cgeom_) :
cgeom(cgeom_), cgeom_const(cgeom_)
{
if (cgeom)
......@@ -167,14 +167,14 @@ public:
}
}
CollisionObject(const boost::shared_ptr<CollisionGeometry> &cgeom_, const Transform3f& tf) :
CollisionObject(const shared_ptr<CollisionGeometry> &cgeom_, const Transform3f& tf) :
cgeom(cgeom_), cgeom_const(cgeom_), t(tf)
{
cgeom->computeLocalAABB();
computeAABB();
}
CollisionObject(const boost::shared_ptr<CollisionGeometry> &cgeom_, const Matrix3f& R, const Vec3f& T):
CollisionObject(const shared_ptr<CollisionGeometry> &cgeom_, const Matrix3f& R, const Vec3f& T):
cgeom(cgeom_), cgeom_const(cgeom_), t(Transform3f(R, T))
{
cgeom->computeLocalAABB();
......@@ -290,21 +290,21 @@ public:
}
/// @brief get geometry from the object instance
const boost::shared_ptr<const CollisionGeometry>& collisionGeometry() const
const shared_ptr<const CollisionGeometry>& collisionGeometry() const
{
return cgeom_const;
}
/// @brief get geometry from the object instance
const boost::shared_ptr<CollisionGeometry>& collisionGeometry()
const shared_ptr<CollisionGeometry>& collisionGeometry()
{
return cgeom;
}
protected:
boost::shared_ptr<CollisionGeometry> cgeom;
boost::shared_ptr<const CollisionGeometry> cgeom_const;
shared_ptr<CollisionGeometry> cgeom;
shared_ptr<const CollisionGeometry> cgeom_const;
Transform3f t;
......
......@@ -43,19 +43,21 @@
namespace hpp {
namespace fcl {
using boost::shared_ptr;
class CollisionObject;
typedef boost::shared_ptr <CollisionObject> CollisionObjectPtr_t;
typedef boost::shared_ptr < const CollisionObject> CollisionObjectConstPtr_t;
typedef shared_ptr <CollisionObject> CollisionObjectPtr_t;
typedef shared_ptr < const CollisionObject> CollisionObjectConstPtr_t;
class CollisionGeometry;
typedef boost::shared_ptr <CollisionGeometry> CollisionGeometryPtr_t;
typedef boost::shared_ptr <const CollisionGeometry>
typedef shared_ptr <CollisionGeometry> CollisionGeometryPtr_t;
typedef shared_ptr <const CollisionGeometry>
CollisionGeometryConstPtr_t;
class Transform3f;
class AABB;
class BVHModelBase;
typedef boost::shared_ptr<BVHModelBase> BVHModelPtr_t;
typedef shared_ptr<BVHModelBase> BVHModelPtr_t;
}
} // namespace hpp
......
......@@ -38,6 +38,7 @@
#ifndef HPP_FCL_MESH_LOADER_ASSIMP_H
#define HPP_FCL_MESH_LOADER_ASSIMP_H
#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/config.hh>
#include <hpp/fcl/BV/OBBRSS.h>
#include <hpp/fcl/BVH/BVH_model.h>
......@@ -95,7 +96,7 @@ template<class BoundingVolume>
inline void meshFromAssimpScene(
const fcl::Vec3f & scale,
const aiScene* scene,
const boost::shared_ptr < BVHModel<BoundingVolume> > & mesh)
const shared_ptr < BVHModel<BoundingVolume> > & mesh)
{
TriangleAndVertices tv;
......@@ -126,7 +127,7 @@ inline void meshFromAssimpScene(
template<class BoundingVolume>
inline void loadPolyhedronFromResource (const std::string & resource_path,
const fcl::Vec3f & scale,
const boost::shared_ptr < BVHModel<BoundingVolume> > & polyhedron)
const shared_ptr < BVHModel<BoundingVolume> > & polyhedron)
{
internal::Loader scene;
scene.load (resource_path);
......
......@@ -38,7 +38,6 @@
#ifndef HPP_FCL_MESH_LOADER_LOADER_H
#define HPP_FCL_MESH_LOADER_LOADER_H
#include <boost/shared_ptr.hpp>
#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/config.hh>
#include <hpp/fcl/data_types.h>
......
......@@ -40,10 +40,10 @@
#define HPP_FCL_OCTREE_H
#include <boost/shared_ptr.hpp>
#include <boost/array.hpp>
#include <octomap/octomap.h>
#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/BV/AABB.h>
#include <hpp/fcl/collision_object.h>
......@@ -56,7 +56,7 @@ namespace fcl
class HPP_FCL_DLLAPI OcTree : public CollisionGeometry
{
private:
boost::shared_ptr<const octomap::OcTree> tree;
shared_ptr<const octomap::OcTree> tree;
FCL_REAL default_occupancy;
......@@ -68,7 +68,7 @@ public:
typedef octomap::OcTreeNode OcTreeNode;
/// @brief construct octree with a given resolution
OcTree(FCL_REAL resolution) : tree(boost::shared_ptr<const octomap::OcTree>(new octomap::OcTree(resolution)))
OcTree(FCL_REAL resolution) : tree(shared_ptr<const octomap::OcTree>(new octomap::OcTree(resolution)))
{
default_occupancy = tree->getOccupancyThres();
......@@ -78,7 +78,7 @@ public:
}
/// @brief construct octree from octomap
OcTree(const boost::shared_ptr<const octomap::OcTree>& tree_) : tree(tree_)
OcTree(const shared_ptr<const octomap::OcTree>& tree_) : tree(tree_)
{
default_occupancy = tree->getOccupancyThres();
......
......@@ -59,7 +59,6 @@
#include <string>
#include <iostream>
#include <boost/thread.hpp>
#include <boost/noncopyable.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <hpp/fcl/config.hh>
......@@ -109,7 +108,7 @@ namespace tools
/// external profiling tools in that it allows the user to count
/// time spent in various bits of code (sub-function granularity)
/// or count how many times certain pieces of code are executed.
class HPP_FCL_DLLAPI Profiler : private boost::noncopyable
class HPP_FCL_DLLAPI Profiler
{
public:
......@@ -170,6 +169,9 @@ public:
start();
}
Profiler(const Profiler&) = delete;
Profiler& operator=(const Profiler&) = delete;
/// @brief Destructor
~Profiler(void)
{
......
......@@ -70,7 +70,6 @@ using namespace boost::python;
using namespace hpp::fcl;
namespace dv = doxygen::visitor;
using boost::shared_ptr;
using boost::noncopyable;
typedef std::vector<Vec3f> Vec3fs;
......
......@@ -67,7 +67,7 @@ void exposeMeshLoader ()
if(!eigenpy::register_symbolic_link_to_registered_type<MeshLoader>())
{
class_ <MeshLoader, boost::shared_ptr<MeshLoader> > ("MeshLoader",
class_ <MeshLoader, shared_ptr<MeshLoader> > ("MeshLoader",
doxygen::class_doc<MeshLoader>(),
init< optional< NODE_TYPE> >((arg("self"),arg("node_type")),
doxygen::constructor_doc<MeshLoader, const NODE_TYPE&>()))
......@@ -80,7 +80,7 @@ void exposeMeshLoader ()
if(!eigenpy::register_symbolic_link_to_registered_type<CachedMeshLoader>())
{
class_ <CachedMeshLoader, bases<MeshLoader>, boost::shared_ptr<CachedMeshLoader> > (
class_ <CachedMeshLoader, bases<MeshLoader>, shared_ptr<CachedMeshLoader> > (
"CachedMeshLoader",
doxygen::class_doc<MeshLoader>(),
init< optional< NODE_TYPE> >((arg("self"),arg("node_type")),
......
......@@ -59,7 +59,7 @@ namespace fcl {
template <typename BV>
BVHModelPtr_t _load (const std::string& filename, const Vec3f& scale)
{
boost::shared_ptr < BVHModel<BV> > polyhedron (new BVHModel<BV>);
shared_ptr < BVHModel<BV> > polyhedron (new BVHModel<BV>);
loadPolyhedronFromResource (filename, scale, polyhedron);
return polyhedron;
}
......@@ -84,7 +84,7 @@ namespace fcl {
CollisionGeometryPtr_t MeshLoader::loadOctree (const std::string& filename)
{
#ifdef HPP_FCL_HAVE_OCTOMAP
boost::shared_ptr<octomap::OcTree> octree (new octomap::OcTree (filename));
shared_ptr<octomap::OcTree> octree (new octomap::OcTree (filename));
return CollisionGeometryPtr_t (new hpp::fcl::OcTree (octree));
#else
throw std::logic_error("hpp-fcl compiled without OctoMap. Cannot create OcTrees.");
......
......@@ -52,13 +52,12 @@
#include "utility.h"
typedef boost::shared_ptr <hpp::fcl::CollisionGeometry> CollisionGeometryPtr_t;
using hpp::fcl::Transform3f;
using hpp::fcl::Vec3f;
using hpp::fcl::CollisionObject;
using hpp::fcl::DistanceResult;
using hpp::fcl::DistanceRequest;
using hpp::fcl::CollisionGeometryPtr_t;
BOOST_AUTO_TEST_CASE(distance_box_box_1)
{
......
......@@ -293,21 +293,21 @@ void generateEnvironments(std::vector<CollisionObject*>& env, double env_scale,
for(std::size_t i = 0; i < n; ++i)
{
Box* box = new Box(5, 10, 20);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(box), transforms[i]));
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(box), transforms[i]));
}
generateRandomTransforms(extents, transforms, n);
for(std::size_t i = 0; i < n; ++i)
{
Sphere* sphere = new Sphere(30);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(sphere), transforms[i]));
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(sphere), transforms[i]));
}
generateRandomTransforms(extents, transforms, n);
for(std::size_t i = 0; i < n; ++i)
{
Cylinder* cylinder = new Cylinder(10, 40);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(cylinder), transforms[i]));
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(cylinder), transforms[i]));
}
}
......@@ -322,7 +322,7 @@ void generateEnvironmentsMesh(std::vector<CollisionObject*>& env, double env_sca
{
BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
generateBVHModel(*model, box, Transform3f());
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(model), transforms[i]));
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model), transforms[i]));
}
generateRandomTransforms(extents, transforms, n);
......@@ -331,7 +331,7 @@ void generateEnvironmentsMesh(std::vector<CollisionObject*>& env, double env_sca
{
BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
generateBVHModel(*model, sphere, Transform3f(), 16, 16);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(model), transforms[i]));
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model), transforms[i]));
}
generateRandomTransforms(extents, transforms, n);
......@@ -340,7 +340,7 @@ void generateEnvironmentsMesh(std::vector<CollisionObject*>& env, double env_sca
{
BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
generateBVHModel(*model, cylinder, Transform3f(), 16, 16);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(model), transforms[i]));
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model), transforms[i]));
}
}
......@@ -360,7 +360,7 @@ void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env, double
int z = i - n_edge * n_edge * x - n_edge * y;
Box* box = new Box(single_size, single_size, single_size);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(box),
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(box),
Transform3f(Vec3f(x * step_size + delta_size + 0.5 * single_size - env_scale,
y * step_size + delta_size + 0.5 * single_size - env_scale,
z * step_size + delta_size + 0.5 * single_size - env_scale))));
......@@ -373,7 +373,7 @@ void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env, double
int z = i - n_edge * n_edge * x - n_edge * y;
Sphere* sphere = new Sphere(single_size / 2);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(sphere),
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(sphere),
Transform3f(Vec3f(x * step_size + delta_size + 0.5 * single_size - env_scale,
y * step_size + delta_size + 0.5 * single_size - env_scale,
z * step_size + delta_size + 0.5 * single_size - env_scale))));
......@@ -386,7 +386,7 @@ void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env, double
int z = i - n_edge * n_edge * x - n_edge * y;
Cylinder* cylinder = new Cylinder(single_size / 2, single_size);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(cylinder),
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(cylinder),
Transform3f(Vec3f(x * step_size + delta_size + 0.5 * single_size - env_scale,
y * step_size + delta_size + 0.5 * single_size - env_scale,
z * step_size + delta_size + 0.5 * single_size - env_scale))));
......@@ -399,7 +399,7 @@ void generateSelfDistanceEnvironments(std::vector<CollisionObject*>& env, double
int z = i - n_edge * n_edge * x - n_edge * y;
Cone* cone = new Cone(single_size / 2, single_size);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(cone),
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(cone),
Transform3f(Vec3f(x * step_size + delta_size + 0.5 * single_size - env_scale,
y * step_size + delta_size + 0.5 * single_size - env_scale,
z * step_size + delta_size + 0.5 * single_size - env_scale))));
......@@ -424,7 +424,7 @@ void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>& env, do
Box box(single_size, single_size, single_size);
BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
generateBVHModel(*model, box, Transform3f());
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(model),
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model),
Transform3f(Vec3f(x * step_size + delta_size + 0.5 * single_size - env_scale,
y * step_size + delta_size + 0.5 * single_size - env_scale,
z * step_size + delta_size + 0.5 * single_size - env_scale))));
......@@ -439,7 +439,7 @@ void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>& env, do
Sphere sphere(single_size / 2);
BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
generateBVHModel(*model, sphere, Transform3f(), 16, 16);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(model),
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model),
Transform3f(Vec3f(x * step_size + delta_size + 0.5 * single_size - env_scale,
y * step_size + delta_size + 0.5 * single_size - env_scale,
z * step_size + delta_size + 0.5 * single_size - env_scale))));
......@@ -454,7 +454,7 @@ void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>& env, do
Cylinder cylinder(single_size / 2, single_size);
BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
generateBVHModel(*model, cylinder, Transform3f(), 16, 16);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(model),
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model),
Transform3f(Vec3f(x * step_size + delta_size + 0.5 * single_size - env_scale,
y * step_size + delta_size + 0.5 * single_size - env_scale,
z * step_size + delta_size + 0.5 * single_size - env_scale))));
......@@ -469,7 +469,7 @@ void generateSelfDistanceEnvironmentsMesh(std::vector<CollisionObject*>& env, do
Cone cone(single_size / 2, single_size);
BVHModel<OBBRSS>* model = new BVHModel<OBBRSS>();
generateBVHModel(*model, cone, Transform3f(), 16, 16);
env.push_back(new CollisionObject(boost::shared_ptr<CollisionGeometry>(model),
env.push_back(new CollisionObject(shared_ptr<CollisionGeometry>(model),
Transform3f(Vec3f(x * step_size + delta_size + 0.5 * single_size - env_scale,
y * step_size + delta_size + 0.5 * single_size - env_scale,
z * step_size + delta_size + 0.5 * single_size - env_scale))));
......
......@@ -73,7 +73,7 @@ void testBVHModelPointCloud()
points[7] << -a, -b, -c;
{
boost::shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
if (model->getNodeType() != BV_AABB
&& model->getNodeType() != BV_KDOP16
......@@ -108,7 +108,7 @@ void testBVHModelPointCloud()
}
{
boost::shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
if (model->getNodeType() != BV_AABB
&& model->getNodeType() != BV_KDOP16
......@@ -146,7 +146,7 @@ void testBVHModelPointCloud()
template<typename BV>
void testBVHModelTriangles()
{
boost::shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
Box box (Vec3f::Ones());
AABB aabb (Vec3f(-1,0,-1), Vec3f(1,1,1));
......@@ -198,7 +198,7 @@ void testBVHModelTriangles()
BOOST_CHECK_EQUAL(model->build_state, BVH_BUILD_STATE_PROCESSED);
Transform3f pose;
boost::shared_ptr<BVHModel<BV> > cropped(BVHExtract(*model, pose, aabb));
shared_ptr<BVHModel<BV> > cropped(BVHExtract(*model, pose, aabb));
BOOST_REQUIRE(cropped);
BOOST_CHECK(cropped->build_state == BVH_BUILD_STATE_PROCESSED);
BOOST_CHECK_EQUAL(cropped->num_vertices, model->num_vertices - 6);
......@@ -236,7 +236,7 @@ void testBVHModelTriangles()
template<typename BV>
void testBVHModelSubModel()
{
boost::shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
shared_ptr<BVHModel<BV> > model(new BVHModel<BV>);
Box box (Vec3f::Ones());
double a = box.halfSide[0];
......@@ -312,7 +312,7 @@ void testLoadPolyhedron ()
rob = (path / "rob.obj").string();
typedef BVHModel<BoundingVolume> Polyhedron_t;
typedef boost::shared_ptr <Polyhedron_t> PolyhedronPtr_t;
typedef shared_ptr <Polyhedron_t> PolyhedronPtr_t;
PolyhedronPtr_t P1 (new Polyhedron_t), P2;
Vec3f scale;
......@@ -340,7 +340,7 @@ void testLoadGerardBauzil ()
std::string env = (path / "staircases_koroibot_hr.dae").string();
typedef BVHModel<BoundingVolume> Polyhedron_t;
typedef boost::shared_ptr <Polyhedron_t> PolyhedronPtr_t;
typedef shared_ptr <Polyhedron_t> PolyhedronPtr_t;
PolyhedronPtr_t P1 (new Polyhedron_t), P2;
Vec3f scale;
......
......@@ -51,7 +51,7 @@
BOOST_AUTO_TEST_CASE(distance_capsule_box)
{
typedef boost::shared_ptr <hpp::fcl::CollisionGeometry> CollisionGeometryPtr_t;
using hpp::fcl::CollisionGeometryPtr_t;
// Capsule of radius 2 and of height 4
CollisionGeometryPtr_t capsuleGeometry (new hpp::fcl::Capsule (2., 4.));
// Box of size 1 by 2 by 4
......
......@@ -51,7 +51,7 @@
BOOST_AUTO_TEST_CASE(distance_capsule_box)
{
typedef boost::shared_ptr <hpp::fcl::CollisionGeometry> CollisionGeometryPtr_t;
typedef hpp::fcl::shared_ptr <hpp::fcl::CollisionGeometry> CollisionGeometryPtr_t;
// Capsule of radius 2 and of height 4
CollisionGeometryPtr_t capsuleGeometry (new hpp::fcl::Capsule (2., 4.));
// Box of size 1 by 2 by 4
......
......@@ -52,7 +52,6 @@
#include "utility.h"
using namespace hpp::fcl;
typedef boost::shared_ptr <CollisionGeometry> CollisionGeometryPtr_t;
BOOST_AUTO_TEST_CASE(collision_capsule_capsule_trivial)
{
......
......@@ -320,7 +320,7 @@ struct mesh_mesh_run_test
BENCHMARK_NEXT();
typedef BVHModel<BV> BVH_t;
typedef boost::shared_ptr<BVH_t> BVHPtr_t;
typedef shared_ptr<BVH_t> BVHPtr_t;
BVHPtr_t model1 (new BVH_t), model2 (new BVH_t);
model1->bv_splitter.reset(new BVSplitter<BV>(splitMethod));
......
......@@ -46,6 +46,7 @@
# include "utility.h"
# include "fcl_resources/config.h"
using hpp::fcl::shared_ptr;
using hpp::fcl::Transform3f;
using hpp::fcl::Vec3f;
using hpp::fcl::Triangle;
......@@ -125,8 +126,8 @@ BOOST_AUTO_TEST_CASE(mesh_mesh)
loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
loadOBJFile((path / "rob.obj").string().c_str(), p2, t2);
boost::shared_ptr < BVHModel <OBBRSS> > m1 (new BVHModel <OBBRSS>);
boost::shared_ptr < BVHModel <OBBRSS> > m2 (new BVHModel <OBBRSS>);
shared_ptr < BVHModel <OBBRSS> > m1 (new BVHModel <OBBRSS>);
shared_ptr < BVHModel <OBBRSS> > m2 (new BVHModel <OBBRSS>);
m1->beginModel();
m1->addSubModel(p1, t1);
......@@ -171,8 +172,8 @@ BOOST_AUTO_TEST_CASE(box_mesh)
loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
boost::shared_ptr < BVHModel <OBBRSS> > m1 (new BVHModel <OBBRSS>);
boost::shared_ptr < hpp::fcl::Box > m2 (new hpp::fcl::Box (500, 200, 150));
shared_ptr < BVHModel <OBBRSS> > m1 (new BVHModel <OBBRSS>);
shared_ptr < hpp::fcl::Box > m2 (new hpp::fcl::Box (500, 200, 150));
m1->beginModel();
m1->addSubModel(p1, t1);
......
......@@ -10,8 +10,8 @@ using namespace hpp::fcl;
int main(int argc, char** argv)
{
boost::shared_ptr<Box> box0(new Box(1,1,1));
boost::shared_ptr<Box> box1(new Box(1,1,1));
shared_ptr<Box> box0(new Box(1,1,1));
shared_ptr<Box> box1(new Box(1,1,1));
GJKSolver_libccd solver;
Vec3f contact_points;
FCL_REAL distance;
......
......@@ -82,7 +82,7 @@ hpp::fcl::OcTree makeOctree (const BVHModel <OBBRSS>& mesh,
CollisionRequest request (hpp::fcl::CONTACT | hpp::fcl::DISTANCE_LOWER_BOUND, 1);
CollisionResult result;
Transform3f tfBox;
octomap::OcTreePtr_t octree (new octomap::OcTree (resolution));
hpp::fcl::OcTreePtr_t octree (new octomap::OcTree (resolution));
for (FCL_REAL x = resolution * floor (m [0]/resolution); x <= M [0];
x += resolution) {
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment