$search
A class describing an environment for a kinematic robot. This is the base (abstract) definition. Different implementations are possible. The class is aware of a set of obstacles and a robot model. The obstacles are placed in different namespaces so they can be added and removed selectively. More...
#include <environment.h>
Classes | |
class | AllowedCollisionMatrix |
Definition of a structure for the allowed collision matrix. More... | |
struct | AllowedContact |
Definition of a contact that is allowed. More... | |
struct | Contact |
Definition of a contact point. More... | |
Public Types | |
enum | BodyType { LINK, ATTACHED, OBJECT } |
Public Member Functions | |
virtual void | addObject (const std::string &ns, shapes::Shape *shape, const btTransform &pose)=0 |
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)=0 |
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)=0 |
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)=0 |
Remove objects from a specific namespace in the collision model. | |
virtual void | clearObjects (void)=0 |
Remove all objects from collision model. | |
virtual EnvironmentModel * | clone (void) const =0 |
Clone the environment. | |
EnvironmentModel (void) | |
virtual bool | getAllCollisionContacts (const std::vector< AllowedContact > &allowedContacts, std::vector< Contact > &contacts, unsigned int num_per_contact=1) const =0 |
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 =0 |
bool | getCollisionContacts (std::vector< Contact > &contacts, unsigned int max_count=1) const |
virtual bool | getCollisionContacts (const std::vector< AllowedContact > &allowedContacts, std::vector< Contact > &contacts, unsigned int max_count=1) const =0 |
Get the list of contacts (collisions). The maximum number of contacts to be returned can be specified. If the value is 0, all found contacts are returned. | |
const AllowedCollisionMatrix & | getCurrentAllowedCollisionMatrix () const |
double | getCurrentLinkPadding (std::string name) const |
std::map< std::string, double > | getCurrentLinkPaddingMap () const |
const AllowedCollisionMatrix & | getDefaultAllowedCollisionMatrix () const |
const std::map< std::string, double > & | getDefaultLinkPaddingMap () const |
const EnvironmentObjects * | getObjects (void) const |
Get the objects currently contained in the model. | |
const planning_models::KinematicModel * | getRobotModel (void) const |
Get the robot model. | |
double | getRobotPadding (void) const |
Get robot padding. | |
double | getRobotScale (void) const |
Get robot scale. | |
bool | getVerbose (void) const |
Check the state of verbosity. | |
virtual bool | hasObject (const std::string &ns) const =0 |
Tells whether or not there is an object with the given name in the collision model. | |
virtual bool | isCollision (void) const =0 |
Check if a model is in collision with environment and self. Contacts are not computed. | |
virtual bool | isEnvironmentCollision (void) const =0 |
Check whether the model is in collision with the environment. Self collisions are not checked. | |
virtual bool | isSelfCollision (void) const =0 |
Check for self collision. Contacts are not computed. | |
void | lock (void) const |
Provide interface to a lock. Use carefully! | |
virtual void | revertAlteredCollisionMatrix () |
reverts to using default settings for allowed collisions | |
virtual void | revertAlteredLinkPadding () |
virtual void | setAlteredCollisionMatrix (const AllowedCollisionMatrix &acm) |
set the matrix for collision touch to use in lieu of the default settings | |
virtual void | setAlteredLinkPadding (const std::map< std::string, double > &link_padding_map) |
virtual void | setRobotModel (const planning_models::KinematicModel *model, const AllowedCollisionMatrix &acm, 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. | |
void | setVerbose (bool verbose) |
Enable/disable verbosity. | |
void | unlock (void) const |
Provide interface to a lock. Use carefully! | |
virtual void | updateAttachedBodies ()=0 |
Update the set of bodies that are attached to the robot (re-creates them). | |
virtual void | updateRobotModel (const planning_models::KinematicState *state)=0 |
Update the positions of the geometry used in collision detection. | |
virtual | ~EnvironmentModel (void) |
Protected Attributes | |
AllowedCollisionMatrix | altered_collision_matrix_ |
std::map< std::string, double > | altered_link_padding_map_ |
AllowedCollisionMatrix | default_collision_matrix_ |
std::map< std::string, double > | default_link_padding_map_ |
double | default_robot_padding_ |
padding used for robot links | |
boost::recursive_mutex | lock_ |
Mutex used to lock the datastructure. | |
EnvironmentObjects * | objects_ |
List of objects contained in the environment. | |
const planning_models::KinematicModel * | robot_model_ |
Loaded robot model. | |
double | robot_scale_ |
Scaling used for robot links. | |
bool | use_altered_collision_matrix_ |
bool | use_altered_link_padding_map_ |
bool | verbose_ |
Flag to indicate whether verbose mode is on. |
A class describing an environment for a kinematic robot. This is the base (abstract) definition. Different implementations are possible. The class is aware of a set of obstacles and a robot model. The obstacles are placed in different namespaces so they can be added and removed selectively.
Definition at line 61 of file environment.h.
Definition at line 65 of file environment.h.
collision_space_ccd::EnvironmentModel::EnvironmentModel | ( | void | ) | [inline] |
Definition at line 181 of file environment.h.
virtual collision_space_ccd::EnvironmentModel::~EnvironmentModel | ( | void | ) | [inline, virtual] |
Definition at line 188 of file environment.h.
virtual void collision_space_ccd::EnvironmentModel::addObject | ( | const std::string & | ns, | |
shapes::Shape * | shape, | |||
const btTransform & | pose | |||
) | [pure 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.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual void collision_space_ccd::EnvironmentModel::addObject | ( | const std::string & | ns, | |
shapes::StaticShape * | shape | |||
) | [pure 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.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual void collision_space_ccd::EnvironmentModel::addObjects | ( | const std::string & | ns, | |
const std::vector< shapes::Shape * > & | shapes, | |||
const std::vector< btTransform > & | poses | |||
) | [pure 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.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual void collision_space_ccd::EnvironmentModel::clearObjects | ( | const std::string & | ns | ) | [pure virtual] |
Remove objects from a specific namespace in the collision model.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual void collision_space_ccd::EnvironmentModel::clearObjects | ( | void | ) | [pure virtual] |
Remove all objects from collision model.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual EnvironmentModel* collision_space_ccd::EnvironmentModel::clone | ( | void | ) | const [pure virtual] |
Clone the environment.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual bool collision_space_ccd::EnvironmentModel::getAllCollisionContacts | ( | const std::vector< AllowedContact > & | allowedContacts, | |
std::vector< Contact > & | contacts, | |||
unsigned int | num_per_contact = 1 | |||
) | const [pure 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.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual void collision_space_ccd::EnvironmentModel::getAttachedBodyPoses | ( | std::map< std::string, std::vector< btTransform > > & | pose_map | ) | const [pure virtual] |
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
bool collision_space_ccd::EnvironmentModel::getCollisionContacts | ( | std::vector< Contact > & | contacts, | |
unsigned int | max_count = 1 | |||
) | const |
Definition at line 350 of file environment.cpp.
virtual bool collision_space_ccd::EnvironmentModel::getCollisionContacts | ( | const std::vector< AllowedContact > & | allowedContacts, | |
std::vector< Contact > & | contacts, | |||
unsigned int | max_count = 1 | |||
) | const [pure virtual] |
Get the list of contacts (collisions). The maximum number of contacts to be returned can be specified. If the value is 0, all found contacts are returned.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
const EnvironmentModel::AllowedCollisionMatrix & collision_space_ccd::EnvironmentModel::getCurrentAllowedCollisionMatrix | ( | ) | const |
Definition at line 416 of file environment.cpp.
double collision_space_ccd::EnvironmentModel::getCurrentLinkPadding | ( | std::string | name | ) | const |
Definition at line 479 of file environment.cpp.
std::map< std::string, double > collision_space_ccd::EnvironmentModel::getCurrentLinkPaddingMap | ( | ) | const |
Definition at line 467 of file environment.cpp.
const EnvironmentModel::AllowedCollisionMatrix & collision_space_ccd::EnvironmentModel::getDefaultAllowedCollisionMatrix | ( | ) | const |
Definition at line 410 of file environment.cpp.
const std::map< std::string, double > & collision_space_ccd::EnvironmentModel::getDefaultLinkPaddingMap | ( | ) | const |
Definition at line 462 of file environment.cpp.
const EnvironmentObjects * collision_space_ccd::EnvironmentModel::getObjects | ( | void | ) | const |
Get the objects currently contained in the model.
Definition at line 366 of file environment.cpp.
const planning_models::KinematicModel * collision_space_ccd::EnvironmentModel::getRobotModel | ( | void | ) | const |
Get the robot model.
Definition at line 371 of file environment.cpp.
double collision_space_ccd::EnvironmentModel::getRobotPadding | ( | void | ) | const |
Get robot padding.
Definition at line 381 of file environment.cpp.
double collision_space_ccd::EnvironmentModel::getRobotScale | ( | void | ) | const |
Get robot scale.
Definition at line 376 of file environment.cpp.
bool collision_space_ccd::EnvironmentModel::getVerbose | ( | void | ) | const |
Check the state of verbosity.
Definition at line 356 of file environment.cpp.
virtual bool collision_space_ccd::EnvironmentModel::hasObject | ( | const std::string & | ns | ) | const [pure virtual] |
Tells whether or not there is an object with the given name in the collision model.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual bool collision_space_ccd::EnvironmentModel::isCollision | ( | void | ) | const [pure virtual] |
Check if a model is in collision with environment and self. Contacts are not computed.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual bool collision_space_ccd::EnvironmentModel::isEnvironmentCollision | ( | void | ) | const [pure virtual] |
Check whether the model is in collision with the environment. Self collisions are not checked.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual bool collision_space_ccd::EnvironmentModel::isSelfCollision | ( | void | ) | const [pure virtual] |
Check for self collision. Contacts are not computed.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
void collision_space_ccd::EnvironmentModel::lock | ( | void | ) | const |
Provide interface to a lock. Use carefully!
Definition at line 399 of file environment.cpp.
void collision_space_ccd::EnvironmentModel::revertAlteredCollisionMatrix | ( | ) | [virtual] |
reverts to using default settings for allowed collisions
Definition at line 431 of file environment.cpp.
void collision_space_ccd::EnvironmentModel::revertAlteredLinkPadding | ( | ) | [virtual] |
Reverts link padding to that set at robot initialization
Reimplemented in collision_space_ccd::EnvironmentModelBVH< BV >.
Definition at line 456 of file environment.cpp.
void collision_space_ccd::EnvironmentModel::setAlteredCollisionMatrix | ( | const AllowedCollisionMatrix & | acm | ) | [virtual] |
set the matrix for collision touch to use in lieu of the default settings
Definition at line 425 of file environment.cpp.
void collision_space_ccd::EnvironmentModel::setAlteredLinkPadding | ( | const std::map< std::string, double > & | link_padding_map | ) | [virtual] |
Sets a temporary robot padding on the indicated links
Reimplemented in collision_space_ccd::EnvironmentModelBVH< BV >.
Definition at line 436 of file environment.cpp.
void collision_space_ccd::EnvironmentModel::setRobotModel | ( | const planning_models::KinematicModel * | model, | |
const AllowedCollisionMatrix & | acm, | |||
const std::map< std::string, double > & | link_padding_map, | |||
double | default_padding = 0.0 , |
|||
double | scale = 1.0 | |||
) | [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 in collision_space_ccd::EnvironmentModelBVH< BV >.
Definition at line 386 of file environment.cpp.
void collision_space_ccd::EnvironmentModel::setVerbose | ( | bool | verbose | ) |
Enable/disable verbosity.
Definition at line 361 of file environment.cpp.
void collision_space_ccd::EnvironmentModel::unlock | ( | void | ) | const |
Provide interface to a lock. Use carefully!
Definition at line 404 of file environment.cpp.
virtual void collision_space_ccd::EnvironmentModel::updateAttachedBodies | ( | ) | [pure virtual] |
Update the set of bodies that are attached to the robot (re-creates them).
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
virtual void collision_space_ccd::EnvironmentModel::updateRobotModel | ( | const planning_models::KinematicState * | state | ) | [pure virtual] |
Update the positions of the geometry used in collision detection.
Implemented in collision_space_ccd::EnvironmentModelBVH< BV >.
Definition at line 336 of file environment.h.
std::map<std::string, double> collision_space_ccd::EnvironmentModel::altered_link_padding_map_ [protected] |
Definition at line 341 of file environment.h.
Definition at line 335 of file environment.h.
std::map<std::string, double> collision_space_ccd::EnvironmentModel::default_link_padding_map_ [protected] |
Definition at line 340 of file environment.h.
double collision_space_ccd::EnvironmentModel::default_robot_padding_ [protected] |
padding used for robot links
Definition at line 333 of file environment.h.
boost::recursive_mutex collision_space_ccd::EnvironmentModel::lock_ [mutable, protected] |
Mutex used to lock the datastructure.
Definition at line 318 of file environment.h.
List of objects contained in the environment.
Definition at line 327 of file environment.h.
const planning_models::KinematicModel* collision_space_ccd::EnvironmentModel::robot_model_ [protected] |
Loaded robot model.
Definition at line 324 of file environment.h.
double collision_space_ccd::EnvironmentModel::robot_scale_ [protected] |
Scaling used for robot links.
Definition at line 330 of file environment.h.
bool collision_space_ccd::EnvironmentModel::use_altered_collision_matrix_ [protected] |
Definition at line 338 of file environment.h.
bool collision_space_ccd::EnvironmentModel::use_altered_link_padding_map_ [protected] |
Definition at line 343 of file environment.h.
bool collision_space_ccd::EnvironmentModel::verbose_ [protected] |
Flag to indicate whether verbose mode is on.
Definition at line 321 of file environment.h.