Provides the interface to the individual collision checking libraries. More...
#include <collision_env.h>

| Public Types | |
| using | ObjectConstPtr = World::ObjectConstPtr | 
| using | ObjectPtr = World::ObjectPtr | 
| Public Member Functions | |
| virtual void | checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const | 
| Check whether the robot model is in collision with itself or the world at a particular state. Any collision between any pair of links is checked for, NO collisions are ignored.  More... | |
| virtual void | checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const | 
| Check whether the robot model is in collision with itself or the world at a particular state. Allowed collisions specified by the allowed collision matrix are taken into account.  More... | |
| virtual void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const =0 | 
| Check whether the robot model is in collision with the world. Any collisions between a robot link and the world are considered. Self collisions are not checked.  More... | |
| virtual void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const =0 | 
| Check whether the robot model is in collision with the world. Allowed collisions are ignored. Self collisions are not checked.  More... | |
| virtual void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2) const =0 | 
| Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Allowed collisions are ignored. Self collisions are not checked.  More... | |
| virtual void | checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix &acm) const =0 | 
| Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Allowed collisions are ignored. Self collisions are not checked.  More... | |
| virtual void | checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const =0 | 
| Check for robot self collision. Any collision between any pair of links is checked for, NO collisions are ignored.  More... | |
| virtual void | checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const =0 | 
| Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account.  More... | |
| CollisionEnv ()=delete | |
| CollisionEnv (const CollisionEnv &other, const WorldPtr &world) | |
| Copy constructor.  More... | |
| CollisionEnv (const moveit::core::RobotModelConstPtr &model, const WorldPtr &world, double padding=0.0, double scale=1.0) | |
| Constructor.  More... | |
| CollisionEnv (const moveit::core::RobotModelConstPtr &model, double padding=0.0, double scale=1.0) | |
| Constructor.  More... | |
| virtual void | distanceRobot (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const =0 | 
| Compute the distance between a robot and the world.  More... | |
| double | distanceRobot (const moveit::core::RobotState &state, bool verbose=false) const | 
| Compute the shortest distance between a robot and the world.  More... | |
| double | distanceRobot (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const | 
| Compute the shortest distance between a robot and the world.  More... | |
| virtual void | distanceSelf (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const =0 | 
| The distance to self-collision given the robot is at state state.  More... | |
| double | distanceSelf (const moveit::core::RobotState &state) const | 
| The distance to self-collision given the robot is at state state.  More... | |
| double | distanceSelf (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const | 
| The distance to self-collision given the robot is at state state, ignoring the distances between links that are allowed to always collide (as specified by.  More... | |
| const std::map< std::string, double > & | getLinkPadding () const | 
| Get the link paddings as a map (from link names to padding value)  More... | |
| double | getLinkPadding (const std::string &link_name) const | 
| Get the link padding for a particular link.  More... | |
| const std::map< std::string, double > & | getLinkScale () const | 
| Get the link scaling as a map (from link names to scale value)  More... | |
| double | getLinkScale (const std::string &link_name) const | 
| Set the scaling for a particular link.  More... | |
| void | getPadding (std::vector< moveit_msgs::LinkPadding > &padding) const | 
| Get the link padding as a vector of messages.  More... | |
| const moveit::core::RobotModelConstPtr & | getRobotModel () const | 
| The kinematic model corresponding to this collision model.  More... | |
| void | getScale (std::vector< moveit_msgs::LinkScale > &scale) const | 
| Get the link scaling as a vector of messages.  More... | |
| const WorldPtr & | getWorld () | 
| const WorldConstPtr & | getWorld () const | 
| void | setLinkPadding (const std::map< std::string, double > &padding) | 
| Set the link paddings using a map (from link names to padding value)  More... | |
| void | setLinkPadding (const std::string &link_name, double padding) | 
| Set the link padding for a particular link.  More... | |
| void | setLinkScale (const std::map< std::string, double > &scale) | 
| Set the link scaling using a map (from link names to scale value)  More... | |
| void | setLinkScale (const std::string &link_name, double scale) | 
| Set the scaling for a particular link.  More... | |
| void | setPadding (const std::vector< moveit_msgs::LinkPadding > &padding) | 
| Set the link padding from a vector of messages.  More... | |
| void | setPadding (double padding) | 
| Set the link padding (for every link)  More... | |
| void | setScale (const std::vector< moveit_msgs::LinkScale > &scale) | 
| Set the link scaling from a vector of messages.  More... | |
| void | setScale (double scale) | 
| Set the link scaling (for every link)  More... | |
| virtual void | setWorld (const WorldPtr &world) | 
| virtual | ~CollisionEnv () | 
| Protected Member Functions | |
| virtual void | updatedPaddingOrScaling (const std::vector< std::string > &links) | 
| When the scale or padding is changed for a set of links by any of the functions in this class, updatedPaddingOrScaling() function is called. This function has an empty default implementation. The intention is to override this function in a derived class to allow for updating additional structures that may need such updating when link scale or padding changes.  More... | |
| Protected Attributes | |
| std::map< std::string, double > | link_padding_ | 
| The internally maintained map (from link names to padding)  More... | |
| std::map< std::string, double > | link_scale_ | 
| The internally maintained map (from link names to scaling)  More... | |
| moveit::core::RobotModelConstPtr | robot_model_ | 
| The kinematic model corresponding to this collision model.  More... | |
| Private Attributes | |
| WorldPtr | world_ | 
| WorldConstPtr | world_const_ | 
Provides the interface to the individual collision checking libraries.
Definition at line 83 of file collision_env.h.
| using collision_detection::CollisionEnv::ObjectConstPtr = World::ObjectConstPtr | 
Definition at line 279 of file collision_env.h.
| using collision_detection::CollisionEnv::ObjectPtr = World::ObjectPtr | 
Definition at line 278 of file collision_env.h.
| 
 | delete | 
| collision_detection::CollisionEnv::CollisionEnv | ( | const moveit::core::RobotModelConstPtr & | model, | 
| double | padding = 0.0, | ||
| double | scale = 1.0 | ||
| ) | 
Constructor.
| model | A robot model to construct the collision robot from | 
| padding | The padding to use for all objects/links on the robot | 
| scale | A common scaling to use for all objects/links on the robot | 
Definition at line 72 of file collision_env.cpp.
| collision_detection::CollisionEnv::CollisionEnv | ( | const moveit::core::RobotModelConstPtr & | model, | 
| const WorldPtr & | world, | ||
| double | padding = 0.0, | ||
| double | scale = 1.0 | ||
| ) | 
Constructor.
| model | A robot model to construct the collision robot from | 
| padding | The padding to use for all objects/links on the robot | 
| scale | A common scaling to use for all objects/links on the robot | 
Definition at line 88 of file collision_env.cpp.
| collision_detection::CollisionEnv::CollisionEnv | ( | const CollisionEnv & | other, | 
| const WorldPtr & | world | ||
| ) | 
Copy constructor.
Definition at line 105 of file collision_env.cpp.
| 
 | inlinevirtual | 
Definition at line 106 of file collision_env.h.
| 
 | virtual | 
Check whether the robot model is in collision with itself or the world at a particular state. Any collision between any pair of links is checked for, NO collisions are ignored.
| req | A CollisionRequest object that encapsulates the collision request | 
| res | A CollisionResult object that encapsulates the collision result | 
| state | The kinematic state for which checks are being made | 
Reimplemented in collision_detection::CollisionEnvDistanceField.
Definition at line 291 of file collision_env.cpp.
| 
 | virtual | 
Check whether the robot model is in collision with itself or the world at a particular state. Allowed collisions specified by the allowed collision matrix are taken into account.
| req | A CollisionRequest object that encapsulates the collision request | 
| res | A CollisionResult object that encapsulates the collision result | 
| state | The kinematic state for which checks are being made | 
| acm | The allowed collision matrix. | 
Reimplemented in collision_detection::CollisionEnvDistanceField.
Definition at line 299 of file collision_env.cpp.
| 
 | pure virtual | 
Check whether the robot model is in collision with the world. Any collisions between a robot link and the world are considered. Self collisions are not checked.
| req | A CollisionRequest object that encapsulates the collision request | 
| res | A CollisionResult object that encapsulates the collision result | 
| robot | The collision model for the robot | 
| state | The kinematic state for which checks are being made | 
Implemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvAllValid.
| 
 | pure virtual | 
Check whether the robot model is in collision with the world. Allowed collisions are ignored. Self collisions are not checked.
| req | A CollisionRequest object that encapsulates the collision request | 
| res | A CollisionResult object that encapsulates the collision result | 
| robot | The collision model for the robot | 
| state | The kinematic state for which checks are being made | 
| acm | The allowed collision matrix. | 
Implemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvAllValid.
| 
 | pure virtual | 
Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Allowed collisions are ignored. Self collisions are not checked.
| req | A CollisionRequest object that encapsulates the collision request | 
| res | A CollisionResult object that encapsulates the collision result | 
| state1 | The kinematic state at the start of the segment for which checks are being made | 
| state2 | The kinematic state at the end of the segment for which checks are being made | 
Implemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvAllValid.
| 
 | pure virtual | 
Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Allowed collisions are ignored. Self collisions are not checked.
| req | A CollisionRequest object that encapsulates the collision request | 
| res | A CollisionResult object that encapsulates the collision result | 
| state1 | The kinematic state at the start of the segment for which checks are being made | 
| state2 | The kinematic state at the end of the segment for which checks are being made | 
| acm | The allowed collision matrix. | 
Implemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvAllValid.
| 
 | pure virtual | 
Check for robot self collision. Any collision between any pair of links is checked for, NO collisions are ignored.
| req | A CollisionRequest object that encapsulates the collision request | 
| res | A CollisionResult object that encapsulates the collision result | 
| state | The kinematic state for which checks are being made | 
Implemented in collision_detection::CollisionEnvAllValid, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvDistanceField.
| 
 | pure virtual | 
Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account.
| req | A CollisionRequest object that encapsulates the collision request | 
| res | A CollisionResult object that encapsulates the collision result | 
| state | The kinematic state for which checks are being made | 
| acm | The allowed collision matrix. | 
Implemented in collision_detection::CollisionEnvAllValid, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvDistanceField.
| 
 | pure virtual | 
Compute the distance between a robot and the world.
| req | A DistanceRequest object that encapsulates the distance request | 
| res | A DistanceResult object that encapsulates the distance result | 
| state | The state for the robot to check distances from | 
Implemented in collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, collision_detection::CollisionEnvAllValid, and collision_detection::CollisionEnvDistanceField.
| 
 | inline | 
Compute the shortest distance between a robot and the world.
| state | The state for the robot to check distances from | 
| verbose | Output debug information about distance checks | 
Definition at line 230 of file collision_env.h.
| 
 | inline | 
Compute the shortest distance between a robot and the world.
| state | The state for the robot to check distances from | 
| acm | Using an allowed collision matrix has the effect of ignoring distances from links that are always allowed to be in collision. | 
| verbose | Output debug information about distance checks | 
Definition at line 247 of file collision_env.h.
| 
 | pure virtual | 
The distance to self-collision given the robot is at state state.
| req | A DistanceRequest object that encapsulates the distance request | 
| res | A DistanceResult object that encapsulates the distance result | 
| state | The state of this robot to consider | 
Implemented in collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, collision_detection::CollisionEnvAllValid, and collision_detection::CollisionEnvDistanceField.
| 
 | inline | 
The distance to self-collision given the robot is at state state.
Definition at line 197 of file collision_env.h.
| 
 | inline | 
The distance to self-collision given the robot is at state state, ignoring the distances between links that are allowed to always collide (as specified by.
| acm) | 
Definition at line 209 of file collision_env.h.
| const std::map< std::string, double > & collision_detection::CollisionEnv::getLinkPadding | ( | ) | const | 
Get the link paddings as a map (from link names to padding value)
Definition at line 179 of file collision_env.cpp.
| double collision_detection::CollisionEnv::getLinkPadding | ( | const std::string & | link_name | ) | const | 
Get the link padding for a particular link.
Definition at line 155 of file collision_env.cpp.
| const std::map< std::string, double > & collision_detection::CollisionEnv::getLinkScale | ( | ) | const | 
Get the link scaling as a map (from link names to scale value)
Definition at line 219 of file collision_env.cpp.
| double collision_detection::CollisionEnv::getLinkScale | ( | const std::string & | link_name | ) | const | 
Set the scaling for a particular link.
Definition at line 196 of file collision_env.cpp.
| void collision_detection::CollisionEnv::getPadding | ( | std::vector< moveit_msgs::LinkPadding > & | padding | ) | const | 
Get the link padding as a vector of messages.
Definition at line 254 of file collision_env.cpp.
| 
 | inline | 
The kinematic model corresponding to this collision model.
Definition at line 282 of file collision_env.h.
| void collision_detection::CollisionEnv::getScale | ( | std::vector< moveit_msgs::LinkScale > & | scale | ) | const | 
Get the link scaling as a vector of messages.
Definition at line 266 of file collision_env.cpp.
| 
 | inline | 
access the world geometry
Definition at line 267 of file collision_env.h.
| 
 | inline | 
access the world geometry
Definition at line 273 of file collision_env.h.
| void collision_detection::CollisionEnv::setLinkPadding | ( | const std::map< std::string, double > & | padding | ) | 
Set the link paddings using a map (from link names to padding value)
Definition at line 164 of file collision_env.cpp.
| void collision_detection::CollisionEnv::setLinkPadding | ( | const std::string & | link_name, | 
| double | padding | ||
| ) | 
Set the link padding for a particular link.
| link_name | The link name to set padding for | 
| padding | The padding to set (in meters) | 
Definition at line 143 of file collision_env.cpp.
| void collision_detection::CollisionEnv::setLinkScale | ( | const std::map< std::string, double > & | scale | ) | 
Set the link scaling using a map (from link names to scale value)
Definition at line 205 of file collision_env.cpp.
| void collision_detection::CollisionEnv::setLinkScale | ( | const std::string & | link_name, | 
| double | scale | ||
| ) | 
Set the scaling for a particular link.
Definition at line 184 of file collision_env.cpp.
| void collision_detection::CollisionEnv::setPadding | ( | const std::vector< moveit_msgs::LinkPadding > & | padding | ) | 
Set the link padding from a vector of messages.
Definition at line 224 of file collision_env.cpp.
| void collision_detection::CollisionEnv::setPadding | ( | double | padding | ) | 
Set the link padding (for every link)
Definition at line 111 of file collision_env.cpp.
| void collision_detection::CollisionEnv::setScale | ( | const std::vector< moveit_msgs::LinkScale > & | scale | ) | 
Set the link scaling from a vector of messages.
Definition at line 239 of file collision_env.cpp.
| void collision_detection::CollisionEnv::setScale | ( | double | scale | ) | 
Set the link scaling (for every link)
Definition at line 127 of file collision_env.cpp.
| 
 | virtual | 
set the world to use. This can be expensive unless the new and old world are empty. Passing NULL will result in a new empty world being created.
Reimplemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvHybrid, collision_detection::CollisionEnvFCL, and collision_detection::CollisionEnvBullet.
Definition at line 282 of file collision_env.cpp.
| 
 | protectedvirtual | 
When the scale or padding is changed for a set of links by any of the functions in this class, updatedPaddingOrScaling() function is called. This function has an empty default implementation. The intention is to override this function in a derived class to allow for updating additional structures that may need such updating when link scale or padding changes.
| links | the names of the links whose padding or scaling were updated | 
Reimplemented in collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvDistanceField.
Definition at line 278 of file collision_env.cpp.
| 
 | protected | 
The internally maintained map (from link names to padding)
Definition at line 345 of file collision_env.h.
| 
 | protected | 
The internally maintained map (from link names to scaling)
Definition at line 348 of file collision_env.h.
| 
 | protected | 
The kinematic model corresponding to this collision model.
Definition at line 342 of file collision_env.h.
| 
 | private | 
Definition at line 351 of file collision_env.h.
| 
 | private | 
Definition at line 352 of file collision_env.h.