37 #ifndef GEOMETRIC_SHAPES_BODIES_ 38 #define GEOMETRIC_SHAPES_BODIES_ 40 #if __cplusplus <= 199711L 41 #error This header requires at least C++11 48 #include <Eigen/Geometry> 64 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
74 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80 typedef std::shared_ptr<Body>
BodyPtr;
111 updateInternalData();
125 updateInternalData();
138 updateInternalData();
148 virtual std::vector<double> getDimensions()
const = 0;
156 Eigen::Vector3d pt(x, y, z);
157 return containsPoint(pt, verbose);
161 virtual bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const = 0;
167 virtual bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
172 virtual double computeVolume()
const = 0;
180 Eigen::Vector3d& result);
191 BodyPtr
cloneAt(
const Eigen::Affine3d& pose)
const 193 return cloneAt(pose, padding_, scale_);
200 virtual BodyPtr cloneAt(
const Eigen::Affine3d& pose,
double padding,
double scaling)
const = 0;
206 virtual void updateInternalData() = 0;
224 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
239 setDimensions(shape);
247 virtual std::vector<double> getDimensions()
const;
249 virtual bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const;
250 virtual double computeVolume()
const;
252 Eigen::Vector3d& result);
255 virtual bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
258 virtual BodyPtr cloneAt(
const Eigen::Affine3d& pose,
double padding,
double scale)
const;
262 virtual void updateInternalData();
273 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
288 setDimensions(shape);
296 virtual std::vector<double> getDimensions()
const;
298 virtual bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const;
299 virtual double computeVolume()
const;
301 Eigen::Vector3d& result);
304 virtual bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
307 virtual BodyPtr cloneAt(
const Eigen::Affine3d& pose,
double padding,
double scale)
const;
311 virtual void updateInternalData();
332 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
347 setDimensions(shape);
355 virtual std::vector<double> getDimensions()
const;
357 virtual bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const;
358 virtual double computeVolume()
const;
360 Eigen::Vector3d& result);
363 virtual bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
366 virtual BodyPtr cloneAt(
const Eigen::Affine3d& pose,
double padding,
double scale)
const;
370 virtual void updateInternalData();
393 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
403 scaled_vertices_ = NULL;
409 scaled_vertices_ = NULL;
410 setDimensions(shape);
418 virtual std::vector<double> getDimensions()
const;
420 virtual bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const;
421 virtual double computeVolume()
const;
425 virtual bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
428 const std::vector<unsigned int>& getTriangles()
const;
432 virtual BodyPtr cloneAt(
const Eigen::Affine3d& pose,
double padding,
double scale)
const;
435 void computeScaledVerticesFromPlaneProjections();
437 void correctVertexOrderFromPlanes();
441 virtual void updateInternalData();
444 unsigned int countVerticesBehindPlane(
const Eigen::Vector4f& planeNormal)
const;
447 bool isPointInsidePlanes(
const Eigen::Vector3d& point)
const;
461 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
484 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
501 void addBody(
Body* body);
504 void addBody(
const shapes::Shape* shape,
const Eigen::Affine3d& pose,
double padding = 0.0);
510 void setPose(
unsigned int i,
const Eigen::Affine3d& pose);
513 std::size_t getCount()
const;
516 bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const;
519 bool containsPoint(
const Eigen::Vector3d& p, std::size_t&
index,
bool verbose =
false)
const;
526 bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir, std::size_t& index,
530 const Body* getBody(
unsigned int i)
const;
537 typedef std::shared_ptr<Body>
BodyPtr;
const Eigen::Affine3d & getPose() const
Retrieve the pose of the body.
Definition of various shapes. No properties such as position are included. These are simply the descr...
void setPose(const Eigen::Affine3d &pose)
Set the pose of the body. Default is identity.
std::vector< unsigned int > triangles_
BodyPtr cloneAt(const Eigen::Affine3d &pose) const
Get a clone of this body, but one that is located at the pose pose.
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
shapes::ShapeType getType() const
Get the type of shape this body represents.
bool containsPoint(double x, double y, double z, bool verbose=false) const
Check if a point is inside the body.
Definition of a cylinder.
EigenSTL::vector_Vector3d vertices_
double getPadding() const
Retrieve the current padding.
std::map< unsigned int, unsigned int > plane_for_triangle_
std::shared_ptr< Body > BodyPtr
Shared pointer to a Body.
std::shared_ptr< MeshData > mesh_data_
std::vector< Body * > bodies_
Box(const shapes::Shape *shape)
Eigen::Vector3d mesh_center_
void setScale(double scale)
If the dimension of the body should be scaled, this method sets the scale. Default is 1...
EigenSTL::vector_Vector4f planes_
Definition of a sphere that bounds another object.
Eigen::Vector3d box_size_
shapes::ShapeType type_
The type of shape this body was constructed from.
std::shared_ptr< const Body > BodyConstPtr
Shared pointer to a const Body.
A basic definition of a shape. Shapes are considered centered at origin.
Definition of a convex mesh. Convex hull is computed for a given shape::Mesh.
Eigen::Vector3d normalB1_
Definition of a cylinder.
EigenSTL::vector_Vector3d * scaled_vertices_
BoundingCylinder bounding_cylinder_
Eigen::Affine3d pose_
The location of the body (position and orientation)
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > vector_Vector4f
ShapeType
A list of known shape types.
double padding_
The scale that was set for this body.
A vector of Body objects.
std::unique_ptr< EigenSTL::vector_Vector3d > scaled_vertices_storage_
Eigen::Vector3d normalB2_
Cylinder(const shapes::Shape *shape)
ConvexMesh(const shapes::Shape *shape)
Sphere(const shapes::Shape *shape)
Eigen::Vector3d box_offset_
void computeBoundingSphere(const std::vector< const Body * > &bodies, BoundingSphere &mergedSphere)
Compute the bounding sphere for a set of bodies and store the resulting sphere in mergedSphere...
A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding s...
void setPadding(double padd)
If constant padding should be added to the body, this method sets the padding. Default is 0...
double scale_
The scale that was set for this body.
double getScale() const
Retrieve the current scale.
This set of classes allows quickly detecting whether a given point is inside an object or not...