37 #ifndef GEOMETRIC_SHAPES_BODIES_ 38 #define GEOMETRIC_SHAPES_BODIES_ 40 #if __cplusplus <= 199711L 41 #error This header requires at least C++11 50 #include <Eigen/Geometry> 66 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
75 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
81 typedef std::shared_ptr<Body>
BodyPtr;
124 setScaleDirty(scale);
125 updateInternalData();
151 setPaddingDirty(padd);
152 updateInternalData();
178 updateInternalData();
197 useDimensions(shape);
201 virtual std::vector<double> getDimensions()
const = 0;
204 virtual std::vector<double> getScaledDimensions()
const = 0;
212 Eigen::Vector3d pt(x, y, z);
213 return containsPoint(pt, verbose);
217 virtual bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const = 0;
224 virtual bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
229 virtual double computeVolume()
const = 0;
237 Eigen::Vector3d& result)
const;
249 virtual void computeBoundingBox(
AABB& bbox)
const = 0;
253 virtual void computeBoundingBox(
OBB& bbox)
const = 0;
256 BodyPtr
cloneAt(
const Eigen::Isometry3d& pose)
const 258 return cloneAt(pose, padding_, scale_);
265 virtual BodyPtr cloneAt(
const Eigen::Isometry3d& pose,
double padding,
double scaling)
const = 0;
270 virtual void updateInternalData() = 0;
289 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
304 setDimensions(shape);
311 setDimensionsDirty(&shape);
313 Eigen::Isometry3d pose = Eigen::Isometry3d::Identity();
314 pose.translation() = sphere.
center;
323 std::vector<double> getDimensions()
const override;
324 std::vector<double> getScaledDimensions()
const override;
326 bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const override;
327 double computeVolume()
const override;
329 Eigen::Vector3d& result)
const override;
332 void computeBoundingBox(
AABB& bbox)
const override;
333 void computeBoundingBox(
OBB& bbox)
const override;
334 bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
337 BodyPtr cloneAt(
const Eigen::Isometry3d& pose,
double padding,
double scale)
const override;
339 void updateInternalData()
override;
353 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
368 setDimensions(shape);
375 setDimensionsDirty(&shape);
376 setPose(cylinder.
pose);
384 std::vector<double> getDimensions()
const override;
385 std::vector<double> getScaledDimensions()
const override;
387 bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const override;
388 double computeVolume()
const override;
390 Eigen::Vector3d& result)
const override;
393 void computeBoundingBox(
AABB& bbox)
const override;
394 void computeBoundingBox(
OBB& bbox)
const override;
395 bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
398 BodyPtr cloneAt(
const Eigen::Isometry3d& pose,
double padding,
double scale)
const override;
400 void updateInternalData()
override;
424 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
439 setDimensions(shape);
445 shapes::Box shape(aabb.sizes()[0], aabb.sizes()[1], aabb.sizes()[2]);
446 setDimensionsDirty(&shape);
448 Eigen::Isometry3d pose = Eigen::Isometry3d::Identity();
449 pose.translation() = aabb.center();
458 std::vector<double> getDimensions()
const override;
459 std::vector<double> getScaledDimensions()
const override;
461 bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const override;
462 double computeVolume()
const override;
464 Eigen::Vector3d& result)
const override;
467 void computeBoundingBox(
AABB& bbox)
const override;
468 void computeBoundingBox(
OBB& bbox)
const override;
469 bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
472 BodyPtr cloneAt(
const Eigen::Isometry3d& pose,
double padding,
double scale)
const override;
474 void updateInternalData()
override;
500 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
510 scaled_vertices_ =
nullptr;
516 scaled_vertices_ =
nullptr;
517 setDimensions(shape);
523 std::vector<double> getDimensions()
const override;
525 std::vector<double> getScaledDimensions()
const override;
527 bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const override;
528 double computeVolume()
const override;
532 void computeBoundingBox(
AABB& bbox)
const override;
533 void computeBoundingBox(
OBB& bbox)
const override;
534 bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir,
537 const std::vector<unsigned int>& getTriangles()
const;
547 BodyPtr cloneAt(
const Eigen::Isometry3d& pose,
double padding,
double scale)
const override;
550 void computeScaledVerticesFromPlaneProjections();
552 void correctVertexOrderFromPlanes();
554 void updateInternalData()
override;
560 unsigned int countVerticesBehindPlane(
const Eigen::Vector4f& planeNormal)
const;
568 bool isPointInsidePlanes(
const Eigen::Vector3d& point)
const;
582 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
605 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
622 void addBody(
Body* body);
625 void addBody(
const shapes::Shape* shape,
const Eigen::Isometry3d& pose,
double padding = 0.0);
631 void setPose(
unsigned int i,
const Eigen::Isometry3d& pose);
634 std::size_t getCount()
const;
637 bool containsPoint(
const Eigen::Vector3d& p,
bool verbose =
false)
const;
640 bool containsPoint(
const Eigen::Vector3d& p, std::size_t&
index,
bool verbose =
false)
const;
647 bool intersectsRay(
const Eigen::Vector3d& origin,
const Eigen::Vector3d& dir, std::size_t& index,
651 const Body* getBody(
unsigned int i)
const;
658 typedef std::shared_ptr<Body>
BodyPtr;
Definition of various shapes. No properties such as position are included. These are simply the descr...
std::vector< unsigned int > triangles_
void setDimensionsDirty(const shapes::Shape *shape)
Set the dimensions of the body (from corresponding shape).
void setScaleDirty(double scale)
If the dimension of the body should be scaled, this method sets the scale.
void setPose(const Eigen::Isometry3d &pose)
Set the pose of the body. Default is identity.
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...
Eigen::Vector3d corner2_
The translated, but not rotated max corner.
Definition of a cylinder Length is along z axis. Origin is at center of mass.
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
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_
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...
Eigen::Isometry3d pose_
The location of the body (position and orientation)
Represents an oriented bounding box.
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_
Cylinder(const BoundingCylinder &cylinder)
ShapeType
A list of known shape types.
double padding_
The scale that was set for this body.
BodyPtr cloneAt(const Eigen::Isometry3d &pose) const
Get a clone of this body, but one that is located at the pose pose.
std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > vector_Vector4d
EigenSTL::vector_Vector4d planes_
A vector of Body objects.
void setPaddingDirty(double padd)
If the dimension of the body should be padded, this method sets the pading.
std::unique_ptr< EigenSTL::vector_Vector3d > scaled_vertices_storage_
double getScale() const
Retrieve the current scale.
double getPadding() const
Retrieve the current padding.
Eigen::Vector3d normalB2_
Cylinder(const shapes::Shape *shape)
Definition of a box Aligned with the XYZ axes.
ConvexMesh(const shapes::Shape *shape)
Eigen::Vector3d corner1_
The translated, but not rotated min corner.
void setPoseDirty(const Eigen::Isometry3d &pose)
Set the pose of the body.
Sphere(const shapes::Shape *shape)
Eigen::Vector3d box_offset_
Represents an axis-aligned bounding box.
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
const Eigen::Isometry3d & getPose() const
Retrieve the pose of the body.
shapes::ShapeType getType() const
Get the type of shape this body represents.
A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding s...
Eigen::Isometry3d i_pose_
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.
Sphere(const BoundingSphere &sphere)
This set of classes allows quickly detecting whether a given point is inside an object or not...