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 | |
struct | AllowedContact |
Definition of a contact that is allowed. More... | |
struct | Contact |
Definition of a contact point. More... | |
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 | addSelfCollisionGroup (const std::vector< std::string > &group1, const std::vector< std::string > &group2) |
Enable self-collision between all links in group 1 and all links in group 2. | |
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 const std::vector < const planning_models::KinematicModel::AttachedBodyModel * > | getAttachedBodies (const std::string link_name) const =0 |
Gets a vector of all the bodies currently attached to a link. | |
virtual const std::vector < const planning_models::KinematicModel::AttachedBodyModel * > | getAttachedBodies (void) const =0 |
Gets a vector of all the bodies currently attached to the robot. | |
bool | getCollisionContacts (std::vector< Contact > &contacts, unsigned int max_count=1) |
virtual bool | getCollisionContacts (const std::vector< AllowedContact > &allowedContacts, std::vector< Contact > &contacts, unsigned int max_count=1)=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. | |
virtual void | getCurrentAllowedCollisionMatrix (std::vector< std::vector< bool > > &matrix, std::map< std::string, unsigned int > &ind) const |
double | getCurrentLinkPadding (std::string name) const |
virtual void | getDefaultAllowedCollisionMatrix (std::vector< std::vector< bool > > &matrix, std::map< std::string, unsigned int > &ind) const =0 |
const EnvironmentObjects * | getObjects (void) const |
Get the objects currently contained in the model. | |
const boost::shared_ptr< 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 | getSelfCollision (void) const |
Check if self collision is enabled. | |
bool | getVerbose (void) const |
Check the state of verbosity. | |
virtual bool | isCollision (void)=0 |
Check if a model is in collision. Contacts are not computed. | |
virtual bool | isSelfCollision (void)=0 |
Check for self collision. Contacts are not computed. | |
void | lock (void) |
Provide interface to a lock. Use carefully! | |
virtual void | removeCollidingObjects (const shapes::Shape *shape, const btTransform &pose)=0 |
Remove objects in the collision space that are collising with the object supplied as argument. | |
virtual void | removeCollidingObjects (const shapes::StaticShape *shape)=0 |
Remove objects in the collision space that are collising with the object supplied as argument. | |
virtual void | removeSelfCollisionGroup (const std::vector< std::string > &group1, const std::vector< std::string > &group2) |
Disable self-collision between all links in group 1 and all links in group 2. | |
virtual void | revertAllowedCollisionMatrix () |
reverts to using default settings for allowed collisions | |
virtual void | revertRobotLinkPadding () |
virtual void | setAllowedCollisionMatrix (const std::vector< std::vector< bool > > &matrix, const std::map< std::string, unsigned int > &ind) |
set the matrix for collision touch to use in lieu of the default settings | |
virtual int | setCollisionCheck (const std::string &link, bool state)=0 |
Enable/Disable collision checking for specific links. Return the previous value of the state (1 or 0) if succesful; -1 otherwise. | |
virtual void | setCollisionCheckAll (bool state)=0 |
Set collision checking for all links to state. | |
virtual void | setCollisionCheckLinks (const std::vector< std::string > &links, bool state)=0 |
Enable/Disable collision checking for a set of links. | |
virtual void | setCollisionCheckOnlyLinks (const std::vector< std::string > &links, bool state)=0 |
Set collision checking for the set of links to state, set collision checking for all other links to !state. | |
virtual void | setRobotLinkPadding (const std::map< std::string, double > &link_padding_map) |
virtual void | setRobotModel (const boost::shared_ptr< const planning_models::KinematicModel > &model, const std::vector< std::string > &links, 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 | setSelfCollision (bool selfCollision) |
Set the status of self collision. | |
void | setVerbose (bool verbose) |
Enable/disable verbosity. | |
void | unlock (void) |
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 | |
std::map< std::string, double > | altered_link_padding_ |
std::map< std::string, double > | link_padding_map_ |
std::map< std::string, unsigned int > | m_collisionLinkIndex |
Map used internally to find the index of a link that we do collision checking for. | |
std::vector< std::string > | m_collisionLinks |
List of links (names) from the robot model that are considered for collision checking. | |
boost::recursive_mutex | m_lock |
Mutex used to lock the datastructure. | |
EnvironmentObjects * | m_objects |
List of objects contained in the environment. | |
boost::shared_ptr< const planning_models::KinematicModel > | m_robotModel |
Loaded robot model. | |
double | m_robotPadd |
Padding used for robot links. | |
double | m_robotScale |
Scaling used for robot links. | |
bool | m_selfCollision |
Flag to indicate whether self collision checking is enabled. | |
std::vector< std::vector< bool > > | m_selfCollisionTest |
Matrix of booleans indicating whether pairs of links can self collide. | |
bool | m_verbose |
Flag to indicate whether verbose mode is on. | |
std::map< std::string, unsigned int > | set_collision_ind_ |
std::vector< std::vector< bool > > | set_collision_matrix_ |
bool | use_set_collision_matrix_ |
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 53 of file environment.h.
collision_space::EnvironmentModel::EnvironmentModel | ( | void | ) | [inline] |
Definition at line 86 of file environment.h.
virtual collision_space::EnvironmentModel::~EnvironmentModel | ( | void | ) | [inline, virtual] |
Definition at line 94 of file environment.h.
virtual void collision_space::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::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
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::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual void collision_space::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::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
void collision_space::EnvironmentModel::addSelfCollisionGroup | ( | const std::vector< std::string > & | group1, | |
const std::vector< std::string > & | group2 | |||
) | [virtual] |
Enable self-collision between all links in group 1 and all links in group 2.
Reimplemented in collision_space::EnvironmentModelODE.
Definition at line 94 of file environment.cpp.
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::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual void collision_space::EnvironmentModel::clearObjects | ( | void | ) | [pure virtual] |
Remove all objects from collision model.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual EnvironmentModel* collision_space::EnvironmentModel::clone | ( | void | ) | const [pure virtual] |
Clone the environment.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual const std::vector<const planning_models::KinematicModel::AttachedBodyModel*> collision_space::EnvironmentModel::getAttachedBodies | ( | const std::string | link_name | ) | const [pure virtual] |
Gets a vector of all the bodies currently attached to a link.
Implemented in collision_space::EnvironmentModelODE.
virtual const std::vector<const planning_models::KinematicModel::AttachedBodyModel*> collision_space::EnvironmentModel::getAttachedBodies | ( | void | ) | const [pure virtual] |
Gets a vector of all the bodies currently attached to the robot.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
bool collision_space::EnvironmentModel::getCollisionContacts | ( | std::vector< Contact > & | contacts, | |
unsigned int | max_count = 1 | |||
) |
Definition at line 40 of file environment.cpp.
virtual bool collision_space::EnvironmentModel::getCollisionContacts | ( | const std::vector< AllowedContact > & | allowedContacts, | |
std::vector< Contact > & | contacts, | |||
unsigned int | max_count = 1 | |||
) | [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::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
void collision_space::EnvironmentModel::getCurrentAllowedCollisionMatrix | ( | std::vector< std::vector< bool > > & | matrix, | |
std::map< std::string, unsigned int > & | ind | |||
) | const [virtual] |
Definition at line 177 of file environment.cpp.
double collision_space::EnvironmentModel::getCurrentLinkPadding | ( | std::string | name | ) | const |
Definition at line 199 of file environment.cpp.
virtual void collision_space::EnvironmentModel::getDefaultAllowedCollisionMatrix | ( | std::vector< std::vector< bool > > & | matrix, | |
std::map< std::string, unsigned int > & | ind | |||
) | const [pure virtual] |
Implemented in collision_space::EnvironmentModelODE.
const collision_space::EnvironmentObjects * collision_space::EnvironmentModel::getObjects | ( | void | ) | const |
Get the objects currently contained in the model.
Definition at line 56 of file environment.cpp.
const boost::shared_ptr< const planning_models::KinematicModel > & collision_space::EnvironmentModel::getRobotModel | ( | void | ) | const |
Get the robot model.
Definition at line 61 of file environment.cpp.
double collision_space::EnvironmentModel::getRobotPadding | ( | void | ) | const |
Get robot padding.
Definition at line 71 of file environment.cpp.
double collision_space::EnvironmentModel::getRobotScale | ( | void | ) | const |
Get robot scale.
Definition at line 66 of file environment.cpp.
bool collision_space::EnvironmentModel::getSelfCollision | ( | void | ) | const |
Check if self collision is enabled.
Definition at line 159 of file environment.cpp.
bool collision_space::EnvironmentModel::getVerbose | ( | void | ) | const |
Check the state of verbosity.
Definition at line 46 of file environment.cpp.
virtual bool collision_space::EnvironmentModel::isCollision | ( | void | ) | [pure virtual] |
Check if a model is in collision. Contacts are not computed.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual bool collision_space::EnvironmentModel::isSelfCollision | ( | void | ) | [pure virtual] |
Check for self collision. Contacts are not computed.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
void collision_space::EnvironmentModel::lock | ( | void | ) |
Provide interface to a lock. Use carefully!
Definition at line 144 of file environment.cpp.
virtual void collision_space::EnvironmentModel::removeCollidingObjects | ( | const shapes::Shape * | shape, | |
const btTransform & | pose | |||
) | [pure virtual] |
Remove objects in the collision space that are collising with the object supplied as argument.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual void collision_space::EnvironmentModel::removeCollidingObjects | ( | const shapes::StaticShape * | shape | ) | [pure virtual] |
Remove objects in the collision space that are collising with the object supplied as argument.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
void collision_space::EnvironmentModel::removeSelfCollisionGroup | ( | const std::vector< std::string > & | group1, | |
const std::vector< std::string > & | group2 | |||
) | [virtual] |
Disable self-collision between all links in group 1 and all links in group 2.
Reimplemented in collision_space::EnvironmentModelODE.
Definition at line 119 of file environment.cpp.
void collision_space::EnvironmentModel::revertAllowedCollisionMatrix | ( | ) | [virtual] |
reverts to using default settings for allowed collisions
Reimplemented in collision_space::EnvironmentModelODE.
Definition at line 171 of file environment.cpp.
void collision_space::EnvironmentModel::revertRobotLinkPadding | ( | ) | [virtual] |
Reverts link padding to that set at robot initialization
Reimplemented in collision_space::EnvironmentModelODE.
Definition at line 195 of file environment.cpp.
void collision_space::EnvironmentModel::setAllowedCollisionMatrix | ( | const std::vector< std::vector< bool > > & | matrix, | |
const std::map< std::string, unsigned int > & | ind | |||
) | [virtual] |
set the matrix for collision touch to use in lieu of the default settings
Reimplemented in collision_space::EnvironmentModelODE.
Definition at line 164 of file environment.cpp.
virtual int collision_space::EnvironmentModel::setCollisionCheck | ( | const std::string & | link, | |
bool | state | |||
) | [pure virtual] |
Enable/Disable collision checking for specific links. Return the previous value of the state (1 or 0) if succesful; -1 otherwise.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual void collision_space::EnvironmentModel::setCollisionCheckAll | ( | bool | state | ) | [pure virtual] |
Set collision checking for all links to state.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual void collision_space::EnvironmentModel::setCollisionCheckLinks | ( | const std::vector< std::string > & | links, | |
bool | state | |||
) | [pure virtual] |
Enable/Disable collision checking for a set of links.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
virtual void collision_space::EnvironmentModel::setCollisionCheckOnlyLinks | ( | const std::vector< std::string > & | links, | |
bool | state | |||
) | [pure virtual] |
Set collision checking for the set of links to state, set collision checking for all other links to !state.
Implemented in collision_space::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
void collision_space::EnvironmentModel::setRobotLinkPadding | ( | 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 187 of file environment.cpp.
void collision_space::EnvironmentModel::setRobotModel | ( | const boost::shared_ptr< const planning_models::KinematicModel > & | model, | |
const std::vector< std::string > & | links, | |||
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::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
Definition at line 76 of file environment.cpp.
void collision_space::EnvironmentModel::setSelfCollision | ( | bool | selfCollision | ) |
Set the status of self collision.
Definition at line 154 of file environment.cpp.
void collision_space::EnvironmentModel::setVerbose | ( | bool | verbose | ) |
Enable/disable verbosity.
Definition at line 51 of file environment.cpp.
void collision_space::EnvironmentModel::unlock | ( | void | ) |
Provide interface to a lock. Use carefully!
Definition at line 149 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::EnvironmentModelBullet, and collision_space::EnvironmentModelODE.
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.
std::map<std::string, double> collision_space::EnvironmentModel::altered_link_padding_ [protected] |
Definition at line 285 of file environment.h.
std::map<std::string, double> collision_space::EnvironmentModel::link_padding_map_ [protected] |
Definition at line 284 of file environment.h.
std::map<std::string, unsigned int> collision_space::EnvironmentModel::m_collisionLinkIndex [protected] |
Map used internally to find the index of a link that we do collision checking for.
Definition at line 255 of file environment.h.
std::vector<std::string> collision_space::EnvironmentModel::m_collisionLinks [protected] |
List of links (names) from the robot model that are considered for collision checking.
Definition at line 252 of file environment.h.
boost::recursive_mutex collision_space::EnvironmentModel::m_lock [protected] |
Mutex used to lock the datastructure.
Definition at line 249 of file environment.h.
List of objects contained in the environment.
Definition at line 271 of file environment.h.
boost::shared_ptr<const planning_models::KinematicModel> collision_space::EnvironmentModel::m_robotModel [protected] |
Loaded robot model.
Definition at line 268 of file environment.h.
double collision_space::EnvironmentModel::m_robotPadd [protected] |
Padding used for robot links.
Definition at line 277 of file environment.h.
double collision_space::EnvironmentModel::m_robotScale [protected] |
Scaling used for robot links.
Definition at line 274 of file environment.h.
bool collision_space::EnvironmentModel::m_selfCollision [protected] |
Flag to indicate whether self collision checking is enabled.
Definition at line 262 of file environment.h.
std::vector< std::vector<bool> > collision_space::EnvironmentModel::m_selfCollisionTest [protected] |
Matrix of booleans indicating whether pairs of links can self collide.
Definition at line 259 of file environment.h.
bool collision_space::EnvironmentModel::m_verbose [protected] |
Flag to indicate whether verbose mode is on.
Definition at line 265 of file environment.h.
std::map<std::string, unsigned int> collision_space::EnvironmentModel::set_collision_ind_ [protected] |
Definition at line 280 of file environment.h.
std::vector<std::vector<bool> > collision_space::EnvironmentModel::set_collision_matrix_ [protected] |
Definition at line 279 of file environment.h.
bool collision_space::EnvironmentModel::use_set_collision_matrix_ [protected] |
Definition at line 282 of file environment.h.