$search
A class describing an environment for a kinematic robot using ODE. More...
#include <environmentBVH.h>
Classes | |
struct | AttGeom |
Geometry for attachment. More... | |
struct | CollisionData |
struct | CollisionNamespace |
struct | LinkGeom |
Geometry for Link. More... | |
struct | ModelInfo |
class | SAPManager |
Public Member Functions | |
virtual void | addObject (const std::string &ns, shapes::Shape *shape, const btTransform &pose) |
Add a collision object to the map. The user releases ownership of the passed object. Memory allocated for the shape is freed by the collision environment. | |
virtual void | addObject (const std::string &ns, shapes::StaticShape *shape) |
Add a static collision object to the map. The user releases ownership of the passed object. Memory allocated for the shape is freed by the collision environment. | |
virtual void | addObjects (const std::string &ns, const std::vector< shapes::Shape * > &shapes, const std::vector< btTransform > &poses) |
Add a set of collision objects to the map. The user releases ownership of the passed objects. Memory allocated for the shapes is freed by the collision environment. | |
virtual void | clearObjects (const std::string &ns) |
Remove objects from a specific namespace in the collision model. | |
virtual void | clearObjects (void) |
Remove all objects from collision model. | |
virtual EnvironmentModel * | clone (void) const |
Clone the environment. | |
EnvironmentModelBVH (void) | |
virtual bool | getAllCollisionContacts (const std::vector< AllowedContact > &allowedContacts, std::vector< Contact > &contacts, unsigned int num_per_contact=1) const |
This function will get the complete list of contacts between any two potentially colliding bodies. The num per contacts specifies the number of contacts per pair that will be returned. | |
virtual void | getAttachedBodyPoses (std::map< std::string, std::vector< btTransform > > &pose_map) const |
virtual bool | getCollisionContacts (const std::vector< AllowedContact > &allowedContacts, std::vector< Contact > &contacts, unsigned int max_count=1) const |
Get the list of contacts (collisions). | |
virtual bool | hasObject (const std::string &ns) const |
Tells whether or not there is an object with the given name in the collision model. | |
virtual bool | isCollision (void) const |
Check if a model is in collision. | |
virtual bool | isEnvironmentCollision (void) const |
Check if a model is in environment collision. | |
virtual bool | isSelfCollision (void) const |
Check if a model is in self collision. | |
virtual void | revertAlteredLinkPadding () |
virtual void | setAlteredLinkPadding (const std::map< std::string, double > &link_padding_map) |
virtual void | setRobotModel (const planning_models::KinematicModel *model, const AllowedCollisionMatrix &allowed_collision_matrix, const std::map< std::string, double > &link_padding_map, double default_padding=0.0, double scale=1.0) |
Add a robot model. Ignore robot links if their name is not specified in the string vector. The scale argument can be used to increase or decrease the size of the robot's bodies (multiplicative factor). The padding can be used to increase or decrease the robot's bodies with by an additive term. | |
virtual void | updateAttachedBodies (const std::map< std::string, double > &link_padding_map) |
Update the set of bodies that are attached to the robot (re-creates them) using the indicated padding or default if non-specified. | |
virtual void | updateAttachedBodies (void) |
Update the set of bodies that are attached to the robot (re-creates them). | |
virtual void | updateRobotModel (const planning_models::KinematicState *state) |
Update the positions of the geometry used in collision detection. | |
virtual | ~EnvironmentModelBVH (void) |
Protected Member Functions | |
void | addAttachedBody (LinkGeom *lg, const planning_models::KinematicModel::AttachedBodyModel *attm, double padd) |
CollisionGeom * | copyGeom (CollisionGeom *geom) const |
CollisionGeom * | createBVHGeom (const shapes::StaticShape *shape) |
CollisionGeom * | createBVHGeom (const shapes::Shape *shape, double scale, double padding) |
void | createBVHRobotModel () |
void | freeMemory (void) |
void | revertAttachedBodiesLinkPadding () |
void | setAttachedBodiesLinkPadding () |
void | testCollision (CollisionData *data) const |
Internal function for collision detection. | |
void | testEnvironmentCollision (CollisionData *data) const |
Internal function for collision detection. | |
void | testObjectCollision (CollisionNamespace *cn, CollisionData *data) const |
Internal function for collision detection. | |
void | testSelfCollision (CollisionData *data) const |
Internal function for collision detection. | |
void | updateGeom (CollisionGeom *geom, const btTransform &pose) const |
Static Protected Member Functions | |
static void | testGeomCollision (CollisionData *data, CollisionGeom *o1, CollisionGeom *o2) |
Protected Attributes | |
std::map< std::string, bool > | attached_bodies_in_collision_matrix_ |
std::map< std::string, CollisionNamespace * > | coll_namespaces_ |
std::map< CollisionGeom *, std::pair< std::string, BodyType > > | geom_lookup_map_ |
ModelInfo | model_geom_ |
bool | previous_set_robot_model_ |
SAPManager | self_geom_manager |
A class describing an environment for a kinematic robot using ODE.
Definition at line 54 of file environmentBVH.h.
collision_space_ccd::EnvironmentModelBVH< BV >::EnvironmentModelBVH | ( | void | ) | [inline] |
Definition at line 49 of file environmentBVH.cpp.
collision_space_ccd::EnvironmentModelBVH< BV >::~EnvironmentModelBVH | ( | void | ) | [inline, virtual] |
Definition at line 55 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::addAttachedBody | ( | LinkGeom * | lg, | |
const planning_models::KinematicModel::AttachedBodyModel * | attm, | |||
double | padd | |||
) | [inline, protected] |
Definition at line 330 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::addObject | ( | const std::string & | ns, | |
shapes::Shape * | shape, | |||
const btTransform & | pose | |||
) | [inline, virtual] |
Add a collision object to the map. The user releases ownership of the passed object. Memory allocated for the shape is freed by the collision environment.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 946 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::addObject | ( | const std::string & | ns, | |
shapes::StaticShape * | shape | |||
) | [inline, virtual] |
Add a static collision object to the map. The user releases ownership of the passed object. Memory allocated for the shape is freed by the collision environment.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 970 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::addObjects | ( | const std::string & | ns, | |
const std::vector< shapes::Shape * > & | shapes, | |||
const std::vector< btTransform > & | poses | |||
) | [inline, virtual] |
Add a set of collision objects to the map. The user releases ownership of the passed objects. Memory allocated for the shapes is freed by the collision environment.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 914 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::clearObjects | ( | const std::string & | ns | ) | [inline, virtual] |
Remove objects from a specific namespace in the collision model.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 1002 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::clearObjects | ( | void | ) | [inline, virtual] |
Remove all objects from collision model.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 990 of file environmentBVH.cpp.
EnvironmentModel * collision_space_ccd::EnvironmentModelBVH< BV >::clone | ( | void | ) | const [inline, virtual] |
Clone the environment.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 1022 of file environmentBVH.cpp.
CollisionGeom * collision_space_ccd::EnvironmentModelBVH< BV >::copyGeom | ( | CollisionGeom * | geom | ) | const [inline, protected] |
Definition at line 1015 of file environmentBVH.cpp.
CollisionGeom * collision_space_ccd::EnvironmentModelBVH< BV >::createBVHGeom | ( | const shapes::StaticShape * | shape | ) | [inline, protected] |
Definition at line 169 of file environmentBVH.cpp.
CollisionGeom * collision_space_ccd::EnvironmentModelBVH< BV >::createBVHGeom | ( | const shapes::Shape * | shape, | |
double | scale, | |||
double | padding | |||
) | [inline, protected] |
Definition at line 187 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::createBVHRobotModel | ( | ) | [inline, protected] |
Definition at line 119 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::freeMemory | ( | void | ) | [inline, protected] |
Definition at line 61 of file environmentBVH.cpp.
bool collision_space_ccd::EnvironmentModelBVH< BV >::getAllCollisionContacts | ( | const std::vector< AllowedContact > & | allowedContacts, | |
std::vector< Contact > & | contacts, | |||
unsigned int | num_per_contact = 1 | |||
) | const [inline, virtual] |
This function will get the complete list of contacts between any two potentially colliding bodies. The num per contacts specifies the number of contacts per pair that will be returned.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 563 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::getAttachedBodyPoses | ( | std::map< std::string, std::vector< btTransform > > & | pose_map | ) | const [inline, virtual] |
Implements collision_space_ccd::EnvironmentModel.
Definition at line 94 of file environmentBVH.cpp.
bool collision_space_ccd::EnvironmentModelBVH< BV >::getCollisionContacts | ( | const std::vector< AllowedContact > & | allowedContacts, | |
std::vector< Contact > & | contacts, | |||
unsigned int | max_count = 1 | |||
) | const [inline, virtual] |
Get the list of contacts (collisions).
Implements collision_space_ccd::EnvironmentModel.
Definition at line 547 of file environmentBVH.cpp.
bool collision_space_ccd::EnvironmentModelBVH< BV >::hasObject | ( | const std::string & | ns | ) | const [inline, virtual] |
Tells whether or not there is an object with the given name in the collision model.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 904 of file environmentBVH.cpp.
bool collision_space_ccd::EnvironmentModelBVH< BV >::isCollision | ( | void | ) | const [inline, virtual] |
Check if a model is in collision.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 581 of file environmentBVH.cpp.
bool collision_space_ccd::EnvironmentModelBVH< BV >::isEnvironmentCollision | ( | void | ) | const [inline, virtual] |
Check if a model is in environment collision.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 601 of file environmentBVH.cpp.
bool collision_space_ccd::EnvironmentModelBVH< BV >::isSelfCollision | ( | void | ) | const [inline, virtual] |
Check if a model is in self collision.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 591 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::revertAlteredLinkPadding | ( | ) | [inline, virtual] |
Reverts link padding to that set at robot initialization
Reimplemented from collision_space_ccd::EnvironmentModel.
Definition at line 510 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::revertAttachedBodiesLinkPadding | ( | ) | [inline, protected] |
Definition at line 405 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::setAlteredLinkPadding | ( | const std::map< std::string, double > & | link_padding_map | ) | [inline, virtual] |
Sets a temporary robot padding on the indicated links
Reimplemented from collision_space_ccd::EnvironmentModel.
Definition at line 470 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::setAttachedBodiesLinkPadding | ( | ) | [inline, protected] |
Definition at line 370 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::setRobotModel | ( | const planning_models::KinematicModel * | model, | |
const AllowedCollisionMatrix & | allowed_collision_matrix, | |||
const std::map< std::string, double > & | link_padding_map, | |||
double | default_padding = 0.0 , |
|||
double | scale = 1.0 | |||
) | [inline, virtual] |
Add a robot model. Ignore robot links if their name is not specified in the string vector. The scale argument can be used to increase or decrease the size of the robot's bodies (multiplicative factor). The padding can be used to increase or decrease the robot's bodies with by an additive term.
Reimplemented from collision_space_ccd::EnvironmentModel.
Definition at line 73 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::testCollision | ( | CollisionData * | data | ) | const [inline, protected] |
Internal function for collision detection.
Definition at line 879 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::testEnvironmentCollision | ( | CollisionData * | data | ) | const [inline, protected] |
Internal function for collision detection.
Definition at line 894 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::testGeomCollision | ( | CollisionData * | data, | |
CollisionGeom * | o1, | |||
CollisionGeom * | o2 | |||
) | [inline, static, protected] |
Definition at line 727 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::testObjectCollision | ( | CollisionNamespace * | cn, | |
CollisionData * | data | |||
) | const [inline, protected] |
Internal function for collision detection.
Definition at line 611 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::testSelfCollision | ( | CollisionData * | data | ) | const [inline, protected] |
Internal function for collision detection.
Definition at line 886 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::updateAttachedBodies | ( | const std::map< std::string, double > & | link_padding_map | ) | [inline, virtual] |
Update the set of bodies that are attached to the robot (re-creates them) using the indicated padding or default if non-specified.
Definition at line 276 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::updateAttachedBodies | ( | void | ) | [inline, virtual] |
Update the set of bodies that are attached to the robot (re-creates them).
Implements collision_space_ccd::EnvironmentModel.
Definition at line 269 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::updateGeom | ( | CollisionGeom * | geom, | |
const btTransform & | pose | |||
) | const [inline, protected] |
Definition at line 263 of file environmentBVH.cpp.
void collision_space_ccd::EnvironmentModelBVH< BV >::updateRobotModel | ( | const planning_models::KinematicState * | state | ) | [inline, virtual] |
Update the positions of the geometry used in collision detection.
Implements collision_space_ccd::EnvironmentModel.
Definition at line 441 of file environmentBVH.cpp.
std::map<std::string, bool> collision_space_ccd::EnvironmentModelBVH< BV >::attached_bodies_in_collision_matrix_ [protected] |
Definition at line 368 of file environmentBVH.h.
std::map<std::string, CollisionNamespace*> collision_space_ccd::EnvironmentModelBVH< BV >::coll_namespaces_ [protected] |
Definition at line 377 of file environmentBVH.h.
std::map<CollisionGeom*, std::pair<std::string, BodyType> > collision_space_ccd::EnvironmentModelBVH< BV >::geom_lookup_map_ [protected] |
Definition at line 379 of file environmentBVH.h.
ModelInfo collision_space_ccd::EnvironmentModelBVH< BV >::model_geom_ [protected] |
Definition at line 376 of file environmentBVH.h.
bool collision_space_ccd::EnvironmentModelBVH< BV >::previous_set_robot_model_ [protected] |
Definition at line 381 of file environmentBVH.h.
SAPManager collision_space_ccd::EnvironmentModelBVH< BV >::self_geom_manager [mutable, protected] |
Definition at line 383 of file environmentBVH.h.