Collision Checker
collision::Shape Class Referenceabstract

Base prototype for the shape of an obstacle. More...

#include <shape.h>

Inheritance diagram for collision::Shape:
collision::CollisionObjectEx collision::solvers::solverFCL::IFCLCollisionObject collision::CollisionObject collision::Point collision::Polygon collision::RectangleAABB collision::RectangleOBB collision::Sphere collision::Triangle

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionObjectClass getCollisionObjectClass () const override
 
virtual const ISolverEntity_FCLgetFclInterface () const override
 
 Shape (const Shape &copy)
 
virtual Shapeclone () const =0
 
Eigen::Vector2d center () const
 Get geometric center of shape. More...
 
double center_x () const
 
double center_y () const
 
void set_center (const Eigen::Vector2d &_center)
 Set geometric center of shape. More...
 
virtual void print (std::ostringstream &stream) const =0
 Print all parameters of the shape. More...
 
virtual CollisionObjectConstPtr timeSlice (int time_idx, CollisionObjectConstPtr shared_ptr_this) const
 
virtual ShapeType type () const =0
 Get shape type. More...
 
double radius () const
 Get radius. More...
 
virtual ~Shape ()
 
- Public Member Functions inherited from collision::CollisionObjectEx
 CollisionObjectEx ()
 
virtual ~CollisionObjectEx ()
 
virtual bool collide (const CollisionObject &c, const collision::CollisionRequest &req=CollisionRequest()) const
 
virtual bool BVCheck (CollisionObjectConstPtr obj2) const
 
virtual std::shared_ptr< const collision::RectangleAABBgetAABB () const
 
virtual int getSolverEntity (solvers::solverFCL::SolverEntity_FCL *&ptr) const
 
virtual int getSolverEntity (solvers::solverBoost::SolverEntity_Boost *&ptr) const
 
virtual const ICollisionContainergetContainerInterface (void) const
 
virtual const solvers::solverBoost::ISolverEntity_BoostgetBoostInterface (void) const
 
- Public Member Functions inherited from collision::CollisionObject
virtual ~CollisionObject ()
 
virtual CollisionObjectType getCollisionObjectType () const
 
virtual void toString (std::ostringstream &stream) const
 
virtual void addParentMap (std::unordered_map< const CollisionObject *, std::list< CollisionObjectConstPtr >> &parent_map) const
 
virtual void addParentMap (std::unordered_map< const CollisionObject *, std::list< CollisionObjectConstPtr >> &parent_map, CollisionObjectConstPtr parent) const
 
virtual bool rayTrace (const Eigen::Vector2d &point1, const Eigen::Vector2d &point2, std::vector< LineSegment > &intersect) const
 

Protected Member Functions

 Shape (const Eigen::Vector2d &_center)
 
- Protected Member Functions inherited from collision::CollisionObjectEx
void invalidateCollisionEntityCache (void)
 

Protected Attributes

Eigen::Vector2d center_
 
double radius_
 

Detailed Description

Base prototype for the shape of an obstacle.

Definition at line 25 of file shape.h.

Constructor & Destructor Documentation

◆ Shape() [1/2]

collision::Shape::Shape ( const Shape copy)

Definition at line 7 of file shape.cc.

◆ ~Shape()

collision::Shape::~Shape ( )
virtual

Definition at line 5 of file shape.cc.

◆ Shape() [2/2]

collision::Shape::Shape ( const Eigen::Vector2d &  _center)
inlineprotected

Definition at line 69 of file shape.h.

Member Function Documentation

◆ center()

Eigen::Vector2d collision::Shape::center ( void  ) const

Get geometric center of shape.

Definition at line 16 of file shape.cc.

◆ center_x()

double collision::Shape::center_x ( ) const

Definition at line 18 of file shape.cc.

◆ center_y()

double collision::Shape::center_y ( ) const

Definition at line 20 of file shape.cc.

◆ clone()

virtual Shape* collision::Shape::clone ( ) const
pure virtual

◆ getCollisionObjectClass()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionObjectClass collision::Shape::getCollisionObjectClass ( ) const
inlineoverridevirtual

Reimplemented from collision::CollisionObject.

Definition at line 29 of file shape.h.

◆ getFclInterface()

virtual const ISolverEntity_FCL* collision::Shape::getFclInterface ( void  ) const
inlineoverridevirtual

Reimplemented from collision::CollisionObjectEx.

Definition at line 33 of file shape.h.

◆ print()

virtual void collision::Shape::print ( std::ostringstream &  stream) const
pure virtual

◆ radius()

double collision::Shape::radius ( ) const

Get radius.

Definition at line 27 of file shape.cc.

◆ set_center()

void collision::Shape::set_center ( const Eigen::Vector2d &  _center)

Set geometric center of shape.

Definition at line 22 of file shape.cc.

◆ timeSlice()

CollisionObjectConstPtr collision::Shape::timeSlice ( int  time_idx,
CollisionObjectConstPtr  shared_ptr_this 
) const
virtual

Implements collision::CollisionObject.

Reimplemented in collision::Polygon.

Definition at line 11 of file shape.cc.

◆ type()

virtual ShapeType collision::Shape::type ( ) const
pure virtual

Member Data Documentation

◆ center_

Eigen::Vector2d collision::Shape::center_
protected

Definition at line 72 of file shape.h.

◆ radius_

double collision::Shape::radius_
protected

Definition at line 73 of file shape.h.


The documentation for this class was generated from the following files: