Public Member Functions
collision_detection::CollisionWorldAllValid Class Reference

#include <collision_world_allvalid.h>

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

List of all members.

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.
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.
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.
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.
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.
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.
 CollisionWorldAllValid ()
 CollisionWorldAllValid (const WorldPtr &world)
 CollisionWorldAllValid (const CollisionWorld &other, const WorldPtr &world)
virtual double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state) const
 Compute the shortest distance between a robot and the world.
virtual double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 Compute the shortest distance between a robot and the world.
virtual double distanceWorld (const CollisionWorld &world) const
 The shortest distance to another world instance (world)
virtual double distanceWorld (const CollisionWorld &world, const AllowedCollisionMatrix &acm) const
 The shortest distance to another world instance (world), ignoring the distances between world elements that are allowed to collide (as specified by acm)

Detailed Description

Definition at line 46 of file collision_world_allvalid.h.


Constructor & Destructor Documentation

Definition at line 39 of file collision_world_allvalid.cpp.

Definition at line 43 of file collision_world_allvalid.cpp.

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]

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

Implements collision_detection::CollisionWorld.

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]

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.

Implements collision_detection::CollisionWorld.

Definition at line 115 of file collision_world_allvalid.cpp.

The shortest distance to another world instance (world)

Implements collision_detection::CollisionWorld.

Definition at line 122 of file collision_world_allvalid.cpp.

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

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

Implements collision_detection::CollisionWorld.

Definition at line 127 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 Mon Jul 24 2017 02:20:44