Public Member Functions | List of all members
collision_detection::CollisionWorldAllValid Class Reference

#include <collision_world_allvalid.h>

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

Public Member Functions

virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
 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
 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
 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
 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
 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
 Check whether a given set of objects is in collision with objects from another world. Allowed collisions are ignored. Any contacts are considered. More...
 
 CollisionWorldAllValid ()
 
 CollisionWorldAllValid (const WorldPtr &world)
 
 CollisionWorldAllValid (const CollisionWorld &other, const WorldPtr &world)
 
virtual double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state) const
 
virtual double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 
virtual void distanceRobot (const DistanceRequest &req, DistanceResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const override
 Compute the distance between a robot and the world. More...
 
virtual double distanceWorld (const CollisionWorld &world) const
 
virtual double distanceWorld (const CollisionWorld &world, const AllowedCollisionMatrix &acm) const
 
virtual void distanceWorld (const DistanceRequest &req, DistanceResult &res, const CollisionWorld &world) const override
 Compute the distance between another world. More...
 
- Public Member Functions inherited from collision_detection::CollisionWorld
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...
 
 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...
 
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...
 
const WorldPtr & getWorld ()
 
const WorldConstPtr & getWorld () const
 
virtual void setWorld (const WorldPtr &world)
 
virtual ~CollisionWorld ()
 

Additional Inherited Members

- Public Types inherited from collision_detection::CollisionWorld
typedef World::ObjectConstPtr ObjectConstPtr
 
typedef World::ObjectPtr ObjectPtr
 

Detailed Description

Definition at line 46 of file collision_world_allvalid.h.

Constructor & Destructor Documentation

collision_detection::CollisionWorldAllValid::CollisionWorldAllValid ( )

Definition at line 39 of file collision_world_allvalid.cpp.

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

Definition at line 43 of file collision_world_allvalid.cpp.

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

Definition at line 47 of file collision_world_allvalid.cpp.

Member Function Documentation

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

Implements collision_detection::CollisionWorld.

Definition at line 52 of file collision_world_allvalid.cpp.

void collision_detection::CollisionWorldAllValid::checkRobotCollision ( 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 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.

Implements collision_detection::CollisionWorld.

Definition at line 61 of file collision_world_allvalid.cpp.

void collision_detection::CollisionWorldAllValid::checkRobotCollision ( 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 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

Implements collision_detection::CollisionWorld.

Definition at line 71 of file collision_world_allvalid.cpp.

void collision_detection::CollisionWorldAllValid::checkRobotCollision ( 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 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.

Implements collision_detection::CollisionWorld.

Definition at line 81 of file collision_world_allvalid.cpp.

void collision_detection::CollisionWorldAllValid::checkWorldCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionWorld other_world 
) const
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

Implements collision_detection::CollisionWorld.

Definition at line 92 of file collision_world_allvalid.cpp.

void collision_detection::CollisionWorldAllValid::checkWorldCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionWorld other_world,
const AllowedCollisionMatrix acm 
) const
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.

Implements collision_detection::CollisionWorld.

Definition at line 100 of file collision_world_allvalid.cpp.

double collision_detection::CollisionWorldAllValid::distanceRobot ( const CollisionRobot robot,
const robot_state::RobotState state 
) const
virtual

Definition at line 109 of file collision_world_allvalid.cpp.

double collision_detection::CollisionWorldAllValid::distanceRobot ( const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const
virtual

Definition at line 115 of file collision_world_allvalid.cpp.

void collision_detection::CollisionWorldAllValid::distanceRobot ( const DistanceRequest req,
DistanceResult res,
const CollisionRobot robot,
const robot_state::RobotState state 
) const
overridevirtual

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

Implements collision_detection::CollisionWorld.

Definition at line 122 of file collision_world_allvalid.cpp.

double collision_detection::CollisionWorldAllValid::distanceWorld ( const CollisionWorld world) const
virtual

Definition at line 130 of file collision_world_allvalid.cpp.

double collision_detection::CollisionWorldAllValid::distanceWorld ( const CollisionWorld world,
const AllowedCollisionMatrix acm 
) const
virtual

Definition at line 135 of file collision_world_allvalid.cpp.

void collision_detection::CollisionWorldAllValid::distanceWorld ( const DistanceRequest req,
DistanceResult res,
const CollisionWorld world 
) const
overridevirtual

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

Implements collision_detection::CollisionWorld.

Definition at line 141 of file collision_world_allvalid.cpp.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05