5 #ifndef __pinocchio_multibody_fcl_hpp__ 6 #define __pinocchio_multibody_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 16 #if !(( defined(_MSC_VER) && _MSC_VER < 1900 ) || ( defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR) )) 21 inline int _snprintf(
char* buffer, std::size_t buf_size,
const char* format, ...)
26 va_start(args, format);
27 res = vsnprintf(buffer, buf_size, format, args);
36 #include <hpp/fcl/collision_object.h> 37 #include <hpp/fcl/collision.h> 38 #include <hpp/fcl/distance.h> 39 #include <hpp/fcl/shape/geometric_shapes.h> 40 #include "pinocchio/spatial/fcl-pinocchio-conversions.hpp" 50 #include <boost/foreach.hpp> 51 #include <boost/shared_ptr.hpp> 56 :
public std::pair<GeomIndex, GeomIndex>
59 typedef std::pair<GeomIndex, GeomIndex>
Base;
74 void disp (std::ostream & os)
const;
79 #ifndef PINOCCHIO_WITH_HPP_FCL 96 AABB(): min_(0), max_(1){};
108 namespace fcl = hpp::fcl;
110 #endif // PINOCCHIO_WITH_HPP_FCL 120 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
142 PINOCCHIO_DEPRECATED CollisionGeometryPtr &
fcl;
184 const CollisionGeometryPtr & collision_geometry,
185 const SE3 & placement,
186 const std::string & meshPath =
"",
187 const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
188 const bool overrideMaterial =
false,
189 const Eigen::Vector4d & meshColor = Eigen::Vector4d::Zero(),
190 const std::string & meshTexturePath =
"")
192 , parentFrame(parent_frame)
193 , parentJoint(parent_joint)
194 , geometry(collision_geometry)
196 , placement(placement)
198 , meshScale(meshScale)
199 , overrideMaterial(overrideMaterial)
200 , meshColor(meshColor)
201 , meshTexturePath(meshTexturePath)
202 , disableCollision(false)
224 const CollisionGeometryPtr & collision_geometry,
225 const SE3 & placement,
226 const std::string & meshPath =
"",
227 const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
228 const bool overrideMaterial =
false,
229 const Eigen::Vector4d & meshColor = Eigen::Vector4d::Zero(),
230 const std::string & meshTexturePath =
"")
233 , parentJoint(parent_joint)
234 , geometry(collision_geometry)
236 , placement(placement)
238 , meshScale(meshScale)
239 , overrideMaterial(overrideMaterial)
240 , meshColor(meshColor)
241 , meshTexturePath(meshTexturePath)
242 , disableCollision(false)
259 parentFrame = other.parentFrame;
260 parentJoint = other.parentJoint;
261 geometry = other.geometry;
262 placement = other.placement;
263 meshPath = other.meshPath;
264 meshScale = other.meshScale;
265 overrideMaterial = other.overrideMaterial;
266 meshColor = other.meshColor;
267 meshTexturePath = other.meshTexturePath;
268 disableCollision = other.disableCollision;
275 #ifdef PINOCCHIO_WITH_HPP_FCL 277 struct ComputeCollision
278 : ::hpp::fcl::ComputeCollision
280 typedef ::hpp::fcl::ComputeCollision
Base;
281 typedef boost::shared_ptr<const fcl::CollisionGeometry> ConstCollisionGeometryPtr;
284 : Base(o1.geometry.get(),o2.geometry.get())
289 virtual ~ComputeCollision() {};
292 ConstCollisionGeometryPtr o1;
293 ConstCollisionGeometryPtr o2;
295 virtual std::size_t
run(
const fcl::Transform3f& tf1,
const fcl::Transform3f& tf2,
296 const fcl::CollisionRequest& request, fcl::CollisionResult& result)
const 299 const_cast<Pointer&
>(Base::o1) = o1.get();
300 const_cast<Pointer&
>(Base::o2) = o2.get();
301 return Base::run(tf1, tf2, request, result);
305 struct ComputeDistance
306 : ::hpp::fcl::ComputeDistance
308 typedef ::hpp::fcl::ComputeDistance
Base;
309 typedef boost::shared_ptr<fcl::CollisionGeometry> ConstCollisionGeometryPtr;
312 : Base(o1.geometry.get(),o2.geometry.get())
317 virtual ~ComputeDistance() {};
320 ConstCollisionGeometryPtr o1;
321 ConstCollisionGeometryPtr o2;
323 virtual hpp::fcl::FCL_REAL
run(
const fcl::Transform3f& tf1,
const fcl::Transform3f& tf2,
324 const fcl::DistanceRequest& request, fcl::DistanceResult& result)
const 327 const_cast<Pointer&
>(Base::o1) = o1.get();
328 const_cast<Pointer&
>(Base::o2) = o2.get();
329 return Base::run(tf1, tf2, request, result);
340 #include "pinocchio/multibody/fcl.hxx" 342 #endif // ifndef __pinocchio_multibody_fcl_hpp__ PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GeometryObject(const std::string &name, const FrameIndex parent_frame, const JointIndex parent_joint, const CollisionGeometryPtr &collision_geometry, const SE3 &placement, const std::string &meshPath="", const Eigen::Vector3d &meshScale=Eigen::Vector3d::Ones(), const bool overrideMaterial=false, const Eigen::Vector4d &meshColor=Eigen::Vector4d::Zero(), const std::string &meshTexturePath="")
Full constructor.
bool operator==(const FakeCollisionGeometry &) const
JointIndex parentJoint
Index of the parent joint.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GeometryObject(const GeometryObject &other)
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
FrameIndex parentFrame
Index of the parent frame.
CollisionGeometryPtr geometry
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
std::pair< GeomIndex, GeomIndex > Base
std::ostream & operator<<(std::ostream &os, const FrameTpl< Scalar, Options > &f)
Eigen::Vector4d meshColor
RGBA color value of the GeometryObject::fcl object.
bool overrideMaterial
Decide whether to override the Material.
FakeCollisionGeometry CollisionGeometry
bool operator==(const aligned_vector< T > &lhs, const aligned_vector< T > &rhs)
PINOCCHIO_COMPILER_DIAGNOSTIC_POP PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS GeometryObject(const std::string &name, const JointIndex parent_joint, const CollisionGeometryPtr &collision_geometry, const SE3 &placement, const std::string &meshPath="", const Eigen::Vector3d &meshScale=Eigen::Vector3d::Ones(), const bool overrideMaterial=false, const Eigen::Vector4d &meshColor=Eigen::Vector4d::Zero(), const std::string &meshTexturePath="")
Reduced constructor.
Main pinocchio namespace.
std::string name
Name of the geometry object.
std::string meshPath
Absolute path to the mesh file (if the fcl pointee is also a Mesh)
EIGEN_DEVICE_FUNC bool operator!=(const array< T, n > &lhs, const array< T, n > &rhs)
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
std::string meshTexturePath
Absolute path to the mesh texture file.
PINOCCHIO_COMPILER_DIAGNOSTIC_POP GeometryObject & operator=(const GeometryObject &other)
SE3 placement
Position of geometry object in parent joint frame.
Eigen::Vector3d meshScale
Scaling vector applied to the GeometryObject::fcl object.
PINOCCHIO_DEPRECATED CollisionGeometryPtr & fcl
The former pointer to the FCL CollisionGeometry.
bool disableCollision
If true, no collision or distance check will be done between the Geometry and any other geometry...