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 | |
typedef std::map< std::string, std::map< std::string, std::vector< AllowedContact > > > | AllowedContactMap |
enum | BodyType { LINK, ATTACHED, OBJECT } |
Public Member Functions | |
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 | addObject (const std::string &ns, shapes::Shape *shape, const tf::Transform &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 | addObjects (const std::string &ns, const std::vector< shapes::Shape * > &shapes, const std::vector< tf::Transform > &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. | |
void | clearAllowedContacts () |
clear out all allowed contacts | |
virtual void | clearObjects (void)=0 |
Remove all objects from collision model. | |
virtual void | clearObjects (const std::string &ns)=0 |
Remove objects from a specific namespace in the collision model. | |
virtual EnvironmentModel * | clone (void) const =0 |
Clone the environment. | |
EnvironmentModel (void) | |
virtual bool | getAllCollisionContacts (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 bool | getAllObjectEnvironmentCollisionContacts (const std::string &object_name, std::vector< Contact > &contacts, unsigned int num_contacts_per_pair) const =0 |
const std::vector < AllowedContact > & | getAllowedContacts () const |
gets the allowed contacts that will be used in collision checking | |
virtual void | getAttachedBodyPoses (std::map< std::string, std::vector< tf::Transform > > &pose_map) const =0 |
virtual bool | getCollisionContacts (std::vector< Contact > &contacts, unsigned int max_total=1, unsigned int max_per_pair=1) const =0 |
Get the list of contacts (collisions). The maximum total number of contacts to be returned can be specified, and the max per pair of objects that are in collision. | |
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 | isObjectInEnvironmentCollision (const std::string &object_name) const =0 |
Check if an object is in collision with the other static objects. | |
virtual bool | isObjectObjectCollision (const std::string &object1_name, const std::string &object2_name) const =0 |
Check if two static objects are in collision. | |
virtual bool | isObjectRobotCollision (const std::string &object_name) const =0 |
Check if a single static object is in collision with the robot. | |
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 | setAllowedContacts (const std::vector< AllowedContact > &allowed_contacts) |
sets the allowed contacts that will be used in collision checking | |
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 | |
AllowedContactMap | allowed_contact_map_ |
std::vector< AllowedContact > | allowed_contacts_ |
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.
typedef std::map<std::string, std::map<std::string, std::vector<AllowedContact> > > collision_space::EnvironmentModel::AllowedContactMap |
Definition at line 103 of file environment.h.
Definition at line 65 of file environment.h.
collision_space::EnvironmentModel::EnvironmentModel | ( | void | ) | [inline] |
Definition at line 187 of file environment.h.
virtual collision_space::EnvironmentModel::~EnvironmentModel | ( | void | ) | [inline, virtual] |
Definition at line 194 of file environment.h.
virtual void collision_space::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::EnvironmentModelODE, and collision_space::EnvironmentModelBullet.
virtual void collision_space::EnvironmentModel::addObject | ( | const std::string & | ns, |
shapes::Shape * | shape, | ||
const tf::Transform & | 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::EnvironmentModelODE, and collision_space::EnvironmentModelBullet.
virtual void collision_space::EnvironmentModel::addObjects | ( | const std::string & | ns, |
const std::vector< shapes::Shape * > & | shapes, | ||
const std::vector< tf::Transform > & | 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::EnvironmentModelODE, and collision_space::EnvironmentModelBullet.
void collision_space::EnvironmentModel::clearAllowedContacts | ( | ) | [inline] |
clear out all allowed contacts
Definition at line 321 of file environment.h.
virtual void collision_space::EnvironmentModel::clearObjects | ( | void | ) | [pure virtual] |
Remove all objects from collision model.
Implemented in collision_space::EnvironmentModelODE, and collision_space::EnvironmentModelBullet.
virtual void collision_space::EnvironmentModel::clearObjects | ( | const std::string & | ns | ) | [pure virtual] |
Remove objects from a specific namespace in the collision model.
Implemented in collision_space::EnvironmentModelODE, and collision_space::EnvironmentModelBullet.
virtual EnvironmentModel* collision_space::EnvironmentModel::clone | ( | void | ) | const [pure virtual] |
Clone the environment.
Implemented in collision_space::EnvironmentModelODE, and collision_space::EnvironmentModelBullet.
virtual bool collision_space::EnvironmentModel::getAllCollisionContacts | ( | 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::EnvironmentModelODE.
virtual bool collision_space::EnvironmentModel::getAllObjectEnvironmentCollisionContacts | ( | const std::string & | object_name, |
std::vector< Contact > & | contacts, | ||
unsigned int | num_contacts_per_pair | ||
) | const [pure virtual] |
Implemented in collision_space::EnvironmentModelODE.
const std::vector< collision_space::EnvironmentModel::AllowedContact > & collision_space::EnvironmentModel::getAllowedContacts | ( | ) | const |
gets the allowed contacts that will be used in collision checking
Definition at line 460 of file environment.cpp.
virtual void collision_space::EnvironmentModel::getAttachedBodyPoses | ( | std::map< std::string, std::vector< tf::Transform > > & | pose_map | ) | const [pure virtual] |
Implemented in collision_space::EnvironmentModelODE.
virtual bool collision_space::EnvironmentModel::getCollisionContacts | ( | std::vector< Contact > & | contacts, |
unsigned int | max_total = 1 , |
||
unsigned int | max_per_pair = 1 |
||
) | const [pure virtual] |
Get the list of contacts (collisions). The maximum total number of contacts to be returned can be specified, and the max per pair of objects that are in collision.
Implemented in collision_space::EnvironmentModelODE.
const collision_space::EnvironmentModel::AllowedCollisionMatrix & collision_space::EnvironmentModel::getCurrentAllowedCollisionMatrix | ( | ) | const |
Definition at line 389 of file environment.cpp.
double collision_space::EnvironmentModel::getCurrentLinkPadding | ( | std::string | name | ) | const |
Definition at line 441 of file environment.cpp.
std::map< std::string, double > collision_space::EnvironmentModel::getCurrentLinkPaddingMap | ( | ) | const |
Definition at line 431 of file environment.cpp.
const collision_space::EnvironmentModel::AllowedCollisionMatrix & collision_space::EnvironmentModel::getDefaultAllowedCollisionMatrix | ( | ) | const |
Definition at line 383 of file environment.cpp.
const std::map< std::string, double > & collision_space::EnvironmentModel::getDefaultLinkPaddingMap | ( | ) | const |
Definition at line 427 of file environment.cpp.
const collision_space::EnvironmentObjects * collision_space::EnvironmentModel::getObjects | ( | void | ) | const |
Get the objects currently contained in the model.
Definition at line 339 of file environment.cpp.
const planning_models::KinematicModel * collision_space::EnvironmentModel::getRobotModel | ( | void | ) | const |
Get the robot model.
Definition at line 344 of file environment.cpp.
double collision_space::EnvironmentModel::getRobotPadding | ( | void | ) | const |
Get robot padding.
Definition at line 354 of file environment.cpp.
double collision_space::EnvironmentModel::getRobotScale | ( | void | ) | const |
Get robot scale.
Definition at line 349 of file environment.cpp.
bool collision_space::EnvironmentModel::getVerbose | ( | void | ) | const |
Check the state of verbosity.
Definition at line 329 of file environment.cpp.
virtual bool collision_space::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::EnvironmentModelODE.
virtual bool collision_space::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::EnvironmentModelODE.
virtual bool collision_space::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::EnvironmentModelODE.
virtual bool collision_space::EnvironmentModel::isObjectInEnvironmentCollision | ( | const std::string & | object_name | ) | const [pure virtual] |
Check if an object is in collision with the other static objects.
Implemented in collision_space::EnvironmentModelODE.
virtual bool collision_space::EnvironmentModel::isObjectObjectCollision | ( | const std::string & | object1_name, |
const std::string & | object2_name | ||
) | const [pure virtual] |
Check if two static objects are in collision.
Implemented in collision_space::EnvironmentModelODE.
virtual bool collision_space::EnvironmentModel::isObjectRobotCollision | ( | const std::string & | object_name | ) | const [pure virtual] |
Check if a single static object is in collision with the robot.
Implemented in collision_space::EnvironmentModelODE.
virtual bool collision_space::EnvironmentModel::isSelfCollision | ( | void | ) | const [pure virtual] |
Check for self collision. Contacts are not computed.
Implemented in collision_space::EnvironmentModelODE.
void collision_space::EnvironmentModel::lock | ( | void | ) | const |
Provide interface to a lock. Use carefully!
Definition at line 372 of file environment.cpp.
void collision_space::EnvironmentModel::revertAlteredCollisionMatrix | ( | ) | [virtual] |
reverts to using default settings for allowed collisions
Definition at line 401 of file environment.cpp.
void collision_space::EnvironmentModel::revertAlteredLinkPadding | ( | ) | [virtual] |
Reverts link padding to that set at robot initialization
Reimplemented in collision_space::EnvironmentModelODE.
Definition at line 422 of file environment.cpp.
void collision_space::EnvironmentModel::setAllowedContacts | ( | const std::vector< AllowedContact > & | allowed_contacts | ) | [virtual] |
sets the allowed contacts that will be used in collision checking
Definition at line 450 of file environment.cpp.
void collision_space::EnvironmentModel::setAlteredCollisionMatrix | ( | const AllowedCollisionMatrix & | acm | ) | [virtual] |
set the matrix for collision touch to use in lieu of the default settings
Definition at line 396 of file environment.cpp.
void collision_space::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::EnvironmentModelODE.
Definition at line 405 of file environment.cpp.
void collision_space::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::EnvironmentModelODE.
Definition at line 359 of file environment.cpp.
void collision_space::EnvironmentModel::setVerbose | ( | bool | verbose | ) |
Enable/disable verbosity.
Definition at line 334 of file environment.cpp.
void collision_space::EnvironmentModel::unlock | ( | void | ) | const |
Provide interface to a lock. Use carefully!
Definition at line 377 of file environment.cpp.
virtual void collision_space::EnvironmentModel::updateAttachedBodies | ( | ) | [pure virtual] |
Update the set of bodies that are attached to the robot (re-creates them)
Implemented in collision_space::EnvironmentModelODE, and collision_space::EnvironmentModelBullet.
virtual void collision_space::EnvironmentModel::updateRobotModel | ( | const planning_models::KinematicState * | state | ) | [pure virtual] |
Update the positions of the geometry used in collision detection.
Implemented in collision_space::EnvironmentModelODE.
Definition at line 375 of file environment.h.
std::vector<AllowedContact> collision_space::EnvironmentModel::allowed_contacts_ [protected] |
Definition at line 376 of file environment.h.
Definition at line 366 of file environment.h.
std::map<std::string, double> collision_space::EnvironmentModel::altered_link_padding_map_ [protected] |
Definition at line 371 of file environment.h.
Definition at line 365 of file environment.h.
std::map<std::string, double> collision_space::EnvironmentModel::default_link_padding_map_ [protected] |
Definition at line 370 of file environment.h.
double collision_space::EnvironmentModel::default_robot_padding_ [protected] |
padding used for robot links
Definition at line 363 of file environment.h.
boost::recursive_mutex collision_space::EnvironmentModel::lock_ [mutable, protected] |
Mutex used to lock the datastructure.
Definition at line 348 of file environment.h.
List of objects contained in the environment.
Definition at line 357 of file environment.h.
const planning_models::KinematicModel* collision_space::EnvironmentModel::robot_model_ [protected] |
Loaded robot model.
Definition at line 354 of file environment.h.
double collision_space::EnvironmentModel::robot_scale_ [protected] |
Scaling used for robot links.
Definition at line 360 of file environment.h.
bool collision_space::EnvironmentModel::use_altered_collision_matrix_ [protected] |
Definition at line 368 of file environment.h.
bool collision_space::EnvironmentModel::use_altered_link_padding_map_ [protected] |
Definition at line 373 of file environment.h.
bool collision_space::EnvironmentModel::verbose_ [protected] |
Flag to indicate whether verbose mode is on.
Definition at line 351 of file environment.h.