5 #ifndef __pinocchio_fcl_hpp__ 6 #define __pinocchio_fcl_hpp__ 8 #include "pinocchio/spatial/se3.hpp" 9 #include "pinocchio/multibody/fwd.hpp" 10 #include "pinocchio/container/aligned-vector.hpp" 12 #ifdef PINOCCHIO_WITH_HPP_FCL 13 #include <hpp/fcl/collision_object.h> 14 #include <hpp/fcl/collision.h> 15 #include <hpp/fcl/distance.h> 16 #include <hpp/fcl/shape/geometric_shapes.h> 17 #include "pinocchio/spatial/fcl-pinocchio-conversions.hpp" 26 #include <boost/foreach.hpp> 27 #include <boost/shared_ptr.hpp> 34 typedef std::pair<GeomIndex, GeomIndex> Base;
38 void disp (std::ostream & os)
const;
39 friend std::ostream & operator << (std::ostream & os,
const CollisionPair & X);
43 #ifndef PINOCCHIO_WITH_HPP_FCL 48 struct FakeCollisionGeometry
50 FakeCollisionGeometry(){};
55 AABB(): min_(0), max_(1){};
60 typedef FakeCollisionGeometry CollisionGeometry;
66 namespace fcl = hpp::fcl;
68 #endif // PINOCCHIO_WITH_HPP_FCL 78 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
94 boost::shared_ptr<fcl::CollisionGeometry>
fcl;
114 GeometryObject(
const std::string & name,
const FrameIndex parentF,
115 const JointIndex parentJ,
116 const boost::shared_ptr<fcl::CollisionGeometry> & collision,
117 const SE3 & placement,
const std::string & meshPath =
"",
118 const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
119 const bool overrideMaterial =
false,
120 const Eigen::Vector4d & meshColor = Eigen::Vector4d::Zero(),
121 const std::string & meshTexturePath =
"")
123 , parentFrame(parentF)
124 , parentJoint(parentJ)
126 , placement(placement)
128 , meshScale(meshScale)
129 , overrideMaterial(overrideMaterial)
130 , meshColor(meshColor)
131 , meshTexturePath(meshTexturePath)
149 friend std::ostream & operator<< (std::ostream & os,
const GeometryObject & geomObject);
158 #include "pinocchio/multibody/fcl.hxx" 161 #endif // ifndef __pinocchio_fcl_hpp__
bool overrideMaterial
Decide whether to override the Material.
Eigen::Vector3d meshScale
Scaling vector applied to the fcl object.
std::string meshTexturePath
Absolute path to the mesh texture file.
JointIndex parentJoint
Index of the parent joint.
std::string name
Name of the geometry object.
std::string meshPath
Absolute path to the mesh file.
Main pinocchio namespace.
SE3 placement
Position of geometry object in parent joint frame.
Eigen::Vector4d meshColor
RGBA color value of the mesh.
FrameIndex parentFrame
Index of the parent frame.
boost::shared_ptr< fcl::CollisionGeometry > fcl
The actual cloud of points representing the collision mesh of the object after scaling.