Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
collision_detection::CollisionWorldFCL Class Reference

#include <collision_world_fcl.h>

Inheritance diagram for collision_detection::CollisionWorldFCL:
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.
 CollisionWorldFCL ()
 CollisionWorldFCL (const WorldPtr &world)
 CollisionWorldFCL (const CollisionWorldFCL &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)
virtual void setWorld (const WorldPtr &world)
virtual ~CollisionWorldFCL ()

Protected Member Functions

void checkRobotCollisionHelper (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
void checkWorldCollisionHelper (const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix *acm) const
void constructFCLObject (const World::Object *obj, FCLObject &fcl_obj) const
double distanceRobotHelper (const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
double distanceWorldHelper (const CollisionWorld &world, const AllowedCollisionMatrix *acm) const
void updateFCLObject (const std::string &id)

Protected Attributes

std::map< std::string, FCLObjectfcl_objs_
boost::scoped_ptr
< fcl::BroadPhaseCollisionManager > 
manager_

Private Member Functions

void initialize ()
void notifyObjectChange (const ObjectConstPtr &obj, World::Action action)

Private Attributes

World::ObserverHandle observer_handle_

Detailed Description

Definition at line 46 of file collision_world_fcl.h.


Constructor & Destructor Documentation

Definition at line 44 of file collision_world_fcl.cpp.

collision_detection::CollisionWorldFCL::CollisionWorldFCL ( const WorldPtr &  world) [explicit]

Definition at line 54 of file collision_world_fcl.cpp.

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

Definition at line 65 of file collision_world_fcl.cpp.

Definition at line 81 of file collision_world_fcl.cpp.


Member Function Documentation

void collision_detection::CollisionWorldFCL::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 86 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::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 93 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::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 101 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::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 109 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::checkRobotCollisionHelper ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const [protected]

Definition at line 118 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::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 137 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::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 143 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::checkWorldCollisionHelper ( const CollisionRequest req,
CollisionResult res,
const CollisionWorld other_world,
const AllowedCollisionMatrix acm 
) const [protected]

Definition at line 150 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::constructFCLObject ( const World::Object obj,
FCLObject fcl_obj 
) const [protected]

Definition at line 163 of file collision_world_fcl.cpp.

double collision_detection::CollisionWorldFCL::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 274 of file collision_world_fcl.cpp.

double collision_detection::CollisionWorldFCL::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 280 of file collision_world_fcl.cpp.

double collision_detection::CollisionWorldFCL::distanceRobotHelper ( const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const [protected]

Definition at line 255 of file collision_world_fcl.cpp.

double collision_detection::CollisionWorldFCL::distanceWorld ( const CollisionWorld world) const [virtual]

The shortest distance to another world instance (world)

Implements collision_detection::CollisionWorld.

Definition at line 287 of file collision_world_fcl.cpp.

double collision_detection::CollisionWorldFCL::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 292 of file collision_world_fcl.cpp.

double collision_detection::CollisionWorldFCL::distanceWorldHelper ( const CollisionWorld world,
const AllowedCollisionMatrix acm 
) const [protected]

Definition at line 298 of file collision_world_fcl.cpp.

Definition at line 234 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::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 from collision_detection::CollisionWorld.

Definition at line 212 of file collision_world_fcl.cpp.

void collision_detection::CollisionWorldFCL::updateFCLObject ( const std::string &  id) [protected]

Definition at line 177 of file collision_world_fcl.cpp.


Member Data Documentation

Definition at line 89 of file collision_world_fcl.h.

boost::scoped_ptr<fcl::BroadPhaseCollisionManager> collision_detection::CollisionWorldFCL::manager_ [protected]

Definition at line 88 of file collision_world_fcl.h.

Definition at line 94 of file collision_world_fcl.h.


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