Public Member Functions | Private Attributes | List of all members
bodies::BodyVector Class Reference

A vector of Body objects. More...

#include <bodies.h>

Public Member Functions

void addBody (Body *body)
 Add a body. More...
 
void addBody (const shapes::Shape *shape, const Eigen::Isometry3d &pose, double padding=0.0)
 Add a body from a shape, a pose for the body and a padding. More...
 
 BodyVector ()
 
 BodyVector (const std::vector< shapes::Shape *> &shapes, const EigenSTL::vector_Isometry3d &poses, double padding=0.0)
 Construct a body vector from a vector of shapes, a vector of poses and a padding. More...
 
void clear ()
 Clear all bodies from the vector. More...
 
bool containsPoint (const Eigen::Vector3d &p, bool verbose=false) const
 Check if any body in the vector contains the input point. More...
 
bool containsPoint (const Eigen::Vector3d &p, std::size_t &index, bool verbose=false) const
 Check if any body contains the input point, and report the first body's index if so. More...
 
const BodygetBody (unsigned int i) const
 Get the ith body in the vector. More...
 
std::size_t getCount () const
 Get the number of bodies in this vector. More...
 
bool intersectsRay (const Eigen::Vector3d &origin, const Eigen::Vector3d &dir, std::size_t &index, EigenSTL::vector_Vector3d *intersections=nullptr, unsigned int count=0) const
 Check if any of the bodies intersects the ray defined by origin and dir. When the first intersection is found, this function terminates. The index of the body that does intersect the ray is set to index (unset if no intersections were found). Optionally, the intersection points are computed and set to intersections (only for the first body that is found to intersect the ray) More...
 
void setPose (unsigned int i, const Eigen::Isometry3d &pose)
 Set the pose of a particular body in the vector of bodies. More...
 
 ~BodyVector ()
 

Private Attributes

std::vector< Body * > bodies_
 

Detailed Description

A vector of Body objects.

Definition at line 611 of file bodies.h.

Constructor & Destructor Documentation

◆ BodyVector() [1/2]

bodies::BodyVector::BodyVector ( )

Definition at line 1336 of file bodies.cpp.

◆ BodyVector() [2/2]

bodies::BodyVector::BodyVector ( const std::vector< shapes::Shape *> &  shapes,
const EigenSTL::vector_Isometry3d poses,
double  padding = 0.0 
)

Construct a body vector from a vector of shapes, a vector of poses and a padding.

Definition at line 1340 of file bodies.cpp.

◆ ~BodyVector()

bodies::BodyVector::~BodyVector ( )

Definition at line 1347 of file bodies.cpp.

Member Function Documentation

◆ addBody() [1/2]

void bodies::BodyVector::addBody ( Body body)

Add a body.

Definition at line 1359 of file bodies.cpp.

◆ addBody() [2/2]

void bodies::BodyVector::addBody ( const shapes::Shape shape,
const Eigen::Isometry3d &  pose,
double  padding = 0.0 
)

Add a body from a shape, a pose for the body and a padding.

Definition at line 1366 of file bodies.cpp.

◆ clear()

void bodies::BodyVector::clear ( )

Clear all bodies from the vector.

Definition at line 1352 of file bodies.cpp.

◆ containsPoint() [1/2]

bool bodies::BodyVector::containsPoint ( const Eigen::Vector3d &  p,
bool  verbose = false 
) const

Check if any body in the vector contains the input point.

Definition at line 1413 of file bodies.cpp.

◆ containsPoint() [2/2]

bool bodies::BodyVector::containsPoint ( const Eigen::Vector3d &  p,
std::size_t &  index,
bool  verbose = false 
) const

Check if any body contains the input point, and report the first body's index if so.

Definition at line 1402 of file bodies.cpp.

◆ getBody()

const bodies::Body * bodies::BodyVector::getBody ( unsigned int  i) const

Get the ith body in the vector.

Definition at line 1391 of file bodies.cpp.

◆ getCount()

std::size_t bodies::BodyVector::getCount ( ) const

Get the number of bodies in this vector.

Definition at line 1375 of file bodies.cpp.

◆ intersectsRay()

bool bodies::BodyVector::intersectsRay ( const Eigen::Vector3d &  origin,
const Eigen::Vector3d &  dir,
std::size_t &  index,
EigenSTL::vector_Vector3d intersections = nullptr,
unsigned int  count = 0 
) const

Check if any of the bodies intersects the ray defined by origin and dir. When the first intersection is found, this function terminates. The index of the body that does intersect the ray is set to index (unset if no intersections were found). Optionally, the intersection points are computed and set to intersections (only for the first body that is found to intersect the ray)

Definition at line 1419 of file bodies.cpp.

◆ setPose()

void bodies::BodyVector::setPose ( unsigned int  i,
const Eigen::Isometry3d &  pose 
)

Set the pose of a particular body in the vector of bodies.

Definition at line 1380 of file bodies.cpp.

Member Data Documentation

◆ bodies_

std::vector<Body*> bodies::BodyVector::bodies_
private

Definition at line 654 of file bodies.h.


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


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Fri Apr 14 2023 02:14:40