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);
39 #include <hpp/fcl/shape/geometric_shapes.h> 40 #include "pinocchio/spatial/fcl-pinocchio-conversions.hpp" 50 #ifdef PINOCCHIO_WITH_HPP_FCL 51 #if HPP_FCL_VERSION_AT_LEAST(2,0,0) 52 #define PINOCCHIO_HPPFCL_USE_STD_SHARED_PTR 56 #ifdef PINOCCHIO_HPPFCL_USE_STD_SHARED_PTR 59 #include <boost/shared_ptr.hpp> 60 #include <boost/make_shared.hpp> 63 #include <boost/foreach.hpp> 67 #ifdef PINOCCHIO_HPPFCL_USE_STD_SHARED_PTR 68 using std::shared_ptr;
69 using std::make_shared;
71 using boost::shared_ptr;
72 using boost::make_shared;
75 :
public std::pair<GeomIndex, GeomIndex>
78 typedef std::pair<GeomIndex, GeomIndex>
Base;
93 void disp (std::ostream & os)
const;
98 #ifndef PINOCCHIO_WITH_HPP_FCL 129 #endif // PINOCCHIO_WITH_HPP_FCL 139 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
161 PINOCCHIO_DEPRECATED CollisionGeometryPtr &
fcl;
203 const CollisionGeometryPtr & collision_geometry,
204 const SE3 & placement,
205 const std::string & meshPath =
"",
206 const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
207 const bool overrideMaterial =
false,
208 const Eigen::Vector4d & meshColor = Eigen::Vector4d(0,0,0,1),
209 const std::string & meshTexturePath =
"")
211 , parentFrame(parent_frame)
212 , parentJoint(parent_joint)
213 , geometry(collision_geometry)
215 , placement(placement)
217 , meshScale(meshScale)
218 , overrideMaterial(overrideMaterial)
219 , meshColor(meshColor)
220 , meshTexturePath(meshTexturePath)
221 , disableCollision(false)
243 const CollisionGeometryPtr & collision_geometry,
244 const SE3 & placement,
245 const std::string & meshPath =
"",
246 const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(),
247 const bool overrideMaterial =
false,
248 const Eigen::Vector4d & meshColor = Eigen::Vector4d::Ones(),
249 const std::string & meshTexturePath =
"")
252 , parentJoint(parent_joint)
253 , geometry(collision_geometry)
255 , placement(placement)
257 , meshScale(meshScale)
258 , overrideMaterial(overrideMaterial)
259 , meshColor(meshColor)
260 , meshTexturePath(meshTexturePath)
261 , disableCollision(false)
278 parentFrame = other.parentFrame;
279 parentJoint = other.parentJoint;
280 geometry = other.geometry;
281 placement = other.placement;
282 meshPath = other.meshPath;
283 meshScale = other.meshScale;
284 overrideMaterial = other.overrideMaterial;
285 meshColor = other.meshColor;
286 meshTexturePath = other.meshTexturePath;
287 disableCollision = other.disableCollision;
294 #ifdef PINOCCHIO_WITH_HPP_FCL 296 struct ComputeCollision
299 typedef ::hpp::fcl::ComputeCollision
Base;
300 typedef shared_ptr<const fcl::CollisionGeometry> ConstCollisionGeometryPtr;
303 :
Base(o1.geometry.get(),o2.geometry.get())
308 virtual ~ComputeCollision() {};
311 ConstCollisionGeometryPtr o1;
312 ConstCollisionGeometryPtr o2;
314 virtual std::size_t
run(
const fcl::Transform3f&
tf1,
const fcl::Transform3f&
tf2,
315 const fcl::CollisionRequest& request, fcl::CollisionResult& result)
const 318 const_cast<Pointer&
>(Base::o1) = o1.get();
319 const_cast<Pointer&
>(Base::o2) = o2.get();
320 return Base::run(tf1, tf2, request, result);
324 struct ComputeDistance
327 typedef ::hpp::fcl::ComputeDistance
Base;
328 typedef shared_ptr<fcl::CollisionGeometry> ConstCollisionGeometryPtr;
331 :
Base(o1.geometry.get(),o2.geometry.get())
336 virtual ~ComputeDistance() {};
339 ConstCollisionGeometryPtr o1;
340 ConstCollisionGeometryPtr o2;
343 const fcl::DistanceRequest& request, fcl::DistanceResult& result)
const 346 const_cast<Pointer&
>(Base::o1) = o1.get();
347 const_cast<Pointer&
>(Base::o2) = o2.get();
348 return Base::run(tf1, tf2, request, result);
359 #include "pinocchio/multibody/fcl.hxx" 361 #endif // ifndef __pinocchio_multibody_fcl_hpp__ EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
JointIndex parentJoint
Index of the parent joint.
bool operator==(const FakeCollisionGeometry &) const
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(0, 0, 0, 1), const std::string &meshTexturePath="")
Full constructor.
bool operator!=(const kIOS_Sphere &other) const
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
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)
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
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::Ones(), const std::string &meshTexturePath="")
Reduced constructor.
std::string meshTexturePath
Absolute path to the mesh texture file.
bool operator==(const kIOS_Sphere &other) const
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...