Public Types | Public Member Functions | Private Attributes | List of all members
collision_detection::CollisionWorld Class Referenceabstract

Perform collision checking with the environment. The collision world maintains a representation of the environment that the robot is operating in. More...

#include <collision_world.h>

Inheritance diagram for collision_detection::CollisionWorld:
Inheritance graph
[legend]

Public Types

typedef World::ObjectConstPtr ObjectConstPtr
 
typedef World::ObjectPtr ObjectPtr
 

Public Member Functions

virtual void checkCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::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 CollisionRobot &robot, const robot_state::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 checkCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
 Check whether the robot model is in collision with itself or the world in a continuous manner (between two robot states) Any collision between any pair of links is checked for, NO collisions are ignored. More...
 
virtual void checkCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
 Check whether the robot model is in collision with itself or the world in a continuous manner (between two robot states). Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::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 CollisionRobot &robot, const robot_state::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 CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const =0
 Check whether the robot model is in collision with the world in a continuous manner (between two robot states). 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 CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::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 checkWorldCollision (const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const =0
 Check whether a given set of objects is in collision with objects from another world. Any contacts are considered. More...
 
virtual void checkWorldCollision (const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix &acm) const =0
 Check whether a given set of objects is in collision with objects from another world. Allowed collisions are ignored. Any contacts are considered. More...
 
 CollisionWorld ()
 
 CollisionWorld (const WorldPtr &world)
 
 CollisionWorld (const CollisionWorld &other, const WorldPtr &world)
 A copy constructor. other should not be changed while the copy constructor is running. world must be the same world as used by other or a (not-yet-modified) copy of the world used by other. More...
 
double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state, bool verbose=false) const
 Compute the shortest distance between a robot and the world. More...
 
double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const
 Compute the shortest distance between a robot and the world. More...
 
virtual void distanceRobot (const DistanceRequest &req, DistanceResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const =0
 Compute the distance between a robot and the world. More...
 
double distanceWorld (const CollisionWorld &world, bool verbose=false) const
 The shortest distance to another world instance (world) More...
 
double distanceWorld (const CollisionWorld &world, const AllowedCollisionMatrix &acm, bool verbose=false) const
 The shortest distance to another world instance (world), ignoring the distances between world elements that are allowed to collide (as specified by acm) More...
 
virtual void distanceWorld (const DistanceRequest &req, DistanceResult &res, const CollisionWorld &world) const =0
 Compute the distance between another world. More...
 
const WorldPtr & getWorld ()
 
const WorldConstPtr & getWorld () const
 
virtual void setWorld (const WorldPtr &world)
 
virtual ~CollisionWorld ()
 

Private Attributes

WorldPtr world_
 
WorldConstPtr world_const_
 

Detailed Description

Perform collision checking with the environment. The collision world maintains a representation of the environment that the robot is operating in.

Definition at line 55 of file collision_world.h.

Member Typedef Documentation

Definition at line 274 of file collision_world.h.

Definition at line 273 of file collision_world.h.

Constructor & Destructor Documentation

collision_detection::CollisionWorld::CollisionWorld ( )

Definition at line 42 of file collision_world.cpp.

collision_detection::CollisionWorld::CollisionWorld ( const WorldPtr &  world)
explicit

Definition at line 46 of file collision_world.cpp.

collision_detection::CollisionWorld::CollisionWorld ( const CollisionWorld other,
const WorldPtr &  world 
)

A copy constructor. other should not be changed while the copy constructor is running. world must be the same world as used by other or a (not-yet-modified) copy of the world used by other.

Definition at line 50 of file collision_world.cpp.

virtual collision_detection::CollisionWorld::~CollisionWorld ( )
inlinevirtual

Definition at line 66 of file collision_world.h.

Member Function Documentation

void collision_detection::CollisionWorld::checkCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state 
) const
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.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result
stateThe kinematic state for which checks are being made

Reimplemented in collision_detection::CollisionWorldDistanceField.

Definition at line 54 of file collision_world.cpp.

void collision_detection::CollisionWorld::checkCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const
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.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result
stateThe kinematic state for which checks are being made
acmThe allowed collision matrix.

Reimplemented in collision_detection::CollisionWorldDistanceField.

Definition at line 62 of file collision_world.cpp.

void collision_detection::CollisionWorld::checkCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state1,
const robot_state::RobotState state2 
) const
virtual

Check whether the robot model is in collision with itself or the world in a continuous manner (between two robot states) Any collision between any pair of links is checked for, NO collisions are ignored.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result
state1The kinematic state at the start of the segment for which checks are being made
state2The kinematic state at the end of the segment for which checks are being made

Definition at line 70 of file collision_world.cpp.

void collision_detection::CollisionWorld::checkCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state1,
const robot_state::RobotState state2,
const AllowedCollisionMatrix acm 
) const
virtual

Check whether the robot model is in collision with itself or the world in a continuous manner (between two robot states). Allowed collisions specified by the allowed collision matrix are taken into account.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result
state1The kinematic state at the start of the segment for which checks are being made
state2The kinematic state at the end of the segment for which checks are being made
acmThe allowed collision matrix.

Definition at line 78 of file collision_world.cpp.

virtual void collision_detection::CollisionWorld::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state 
) const
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.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result robot The collision model for the robot
stateThe kinematic state for which checks are being made

Implemented in collision_detection::CollisionWorldDistanceField, collision_detection::CollisionWorldFCL, and collision_detection::CollisionWorldAllValid.

virtual void collision_detection::CollisionWorld::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const
pure virtual

Check whether the robot model is in collision with the world. Allowed collisions are ignored. Self collisions are not checked.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result robot The collision model for the robot
stateThe kinematic state for which checks are being made
acmThe allowed collision matrix.

Implemented in collision_detection::CollisionWorldDistanceField, collision_detection::CollisionWorldFCL, and collision_detection::CollisionWorldAllValid.

virtual void collision_detection::CollisionWorld::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state1,
const robot_state::RobotState state2 
) const
pure virtual

Check whether the robot model is in collision with the world in a continuous manner (between two robot states). Any collisions between a robot link and the world are considered. Self collisions are not checked.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result robot The collision model for the robot
state1The kinematic state at the start of the segment for which checks are being made
state2The kinematic state at the end of the segment for which checks are being made

Implemented in collision_detection::CollisionWorldDistanceField, collision_detection::CollisionWorldFCL, and collision_detection::CollisionWorldAllValid.

virtual void collision_detection::CollisionWorld::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state1,
const robot_state::RobotState state2,
const AllowedCollisionMatrix acm 
) const
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.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result robot The collision model for the robot
state1The kinematic state at the start of the segment for which checks are being made
state2The kinematic state at the end of the segment for which checks are being made
acmThe allowed collision matrix.

Implemented in collision_detection::CollisionWorldDistanceField, collision_detection::CollisionWorldFCL, and collision_detection::CollisionWorldAllValid.

virtual void collision_detection::CollisionWorld::checkWorldCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionWorld other_world 
) const
pure virtual

Check whether a given set of objects is in collision with objects from another world. Any contacts are considered.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result
other_worldThe other collision world

Implemented in collision_detection::CollisionWorldDistanceField, collision_detection::CollisionWorldAllValid, and collision_detection::CollisionWorldFCL.

virtual void collision_detection::CollisionWorld::checkWorldCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionWorld other_world,
const AllowedCollisionMatrix acm 
) const
pure virtual

Check whether a given set of objects is in collision with objects from another world. Allowed collisions are ignored. Any contacts are considered.

Parameters
reqA CollisionRequest object that encapsulates the collision request
resA CollisionResult object that encapsulates the collision result
other_worldThe other collision world
acmThe allowed collision matrix.

Implemented in collision_detection::CollisionWorldDistanceField, collision_detection::CollisionWorldAllValid, and collision_detection::CollisionWorldFCL.

double collision_detection::CollisionWorld::distanceRobot ( const CollisionRobot robot,
const robot_state::RobotState state,
bool  verbose = false 
) const
inline

Compute the shortest distance between a robot and the world.

Parameters
robotThe robot to check distance for
stateThe state for the robot to check distances from
verboseOutput debug information about distance checks

Definition at line 180 of file collision_world.h.

double collision_detection::CollisionWorld::distanceRobot ( const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm,
bool  verbose = false 
) const
inline

Compute the shortest distance between a robot and the world.

Parameters
robotThe robot to check distance for
stateThe state for the robot to check distances from
acmUsing an allowed collision matrix has the effect of ignoring distances from links that are always allowed to be in collision.
verboseOutput debug information about distance checks

Definition at line 199 of file collision_world.h.

virtual void collision_detection::CollisionWorld::distanceRobot ( const DistanceRequest req,
DistanceResult res,
const CollisionRobot robot,
const robot_state::RobotState state 
) const
pure virtual

Compute the distance between a robot and the world.

Parameters
reqA DistanceRequest object that encapsulates the distance request
resA DistanceResult object that encapsulates the distance result
robotThe robot to check distance for
stateThe state for the robot to check distances from

Implemented in collision_detection::CollisionWorldDistanceField, collision_detection::CollisionWorldAllValid, and collision_detection::CollisionWorldFCL.

double collision_detection::CollisionWorld::distanceWorld ( const CollisionWorld world,
bool  verbose = false 
) const
inline

The shortest distance to another world instance (world)

Parameters
verboseOutput debug information about distance checks

Definition at line 223 of file collision_world.h.

double collision_detection::CollisionWorld::distanceWorld ( const CollisionWorld world,
const AllowedCollisionMatrix acm,
bool  verbose = false 
) const
inline

The shortest distance to another world instance (world), ignoring the distances between world elements that are allowed to collide (as specified by acm)

Parameters
verboseOutput debug information about distance checks

Definition at line 237 of file collision_world.h.

virtual void collision_detection::CollisionWorld::distanceWorld ( const DistanceRequest req,
DistanceResult res,
const CollisionWorld world 
) const
pure virtual

Compute the distance between another world.

Parameters
reqA DistanceRequest object that encapsulates the distance request
resA DistanceResult object that encapsulates the distance result
worldThe world to check distance for

Implemented in collision_detection::CollisionWorldDistanceField, collision_detection::CollisionWorldAllValid, and collision_detection::CollisionWorldFCL.

const WorldPtr& collision_detection::CollisionWorld::getWorld ( )
inline

access the world geometry

Definition at line 262 of file collision_world.h.

const WorldConstPtr& collision_detection::CollisionWorld::getWorld ( ) const
inline

access the world geometry

Definition at line 268 of file collision_world.h.

void collision_detection::CollisionWorld::setWorld ( const WorldPtr &  world)
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::CollisionWorldDistanceField, collision_detection::CollisionWorldHybrid, and collision_detection::CollisionWorldFCL.

Definition at line 87 of file collision_world.cpp.

Member Data Documentation

WorldPtr collision_detection::CollisionWorld::world_
private

Definition at line 277 of file collision_world.h.

WorldConstPtr collision_detection::CollisionWorld::world_const_
private

Definition at line 278 of file collision_world.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:34