Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
collision_detection::CollisionWorldFCL Class Reference

#include <collision_world_fcl.h>

Inheritance diagram for collision_detection::CollisionWorldFCL:
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...
 
 CollisionWorldFCL ()
 
 CollisionWorldFCL (const WorldPtr &world)
 
 CollisionWorldFCL (const CollisionWorldFCL &other, const WorldPtr &world)
 
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 void distanceWorld (const DistanceRequest &req, DistanceResult &res, const CollisionWorld &world) const override
 Compute the distance between another world. More...
 
virtual void setWorld (const WorldPtr &world)
 
virtual ~CollisionWorldFCL ()
 
- 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 ~CollisionWorld ()
 

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
 
void updateFCLObject (const std::string &id)
 

Protected Attributes

std::map< std::string, FCLObjectfcl_objs_
 
std::unique_ptr< fcl::BroadPhaseCollisionManager > manager_
 

Private Member Functions

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

Private Attributes

World::ObserverHandle observer_handle_
 

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_fcl.h.

Constructor & Destructor Documentation

collision_detection::CollisionWorldFCL::CollisionWorldFCL ( )

Definition at line 49 of file collision_world_fcl.cpp.

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

Definition at line 59 of file collision_world_fcl.cpp.

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

Definition at line 70 of file collision_world_fcl.cpp.

collision_detection::CollisionWorldFCL::~CollisionWorldFCL ( )
virtual

Definition at line 86 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 91 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 97 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 104 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 111 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 119 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 145 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 151 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 157 of file collision_world_fcl.cpp.

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

Definition at line 177 of file collision_world_fcl.cpp.

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

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

void collision_detection::CollisionWorldFCL::initialize ( )
private
void collision_detection::CollisionWorldFCL::notifyObjectChange ( const ObjectConstPtr obj,
World::Action  action 
)
private

Definition at line 248 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.

Reimplemented in collision_detection::CollisionWorldHybrid.

Definition at line 226 of file collision_world_fcl.cpp.

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

Definition at line 191 of file collision_world_fcl.cpp.

Member Data Documentation

std::map<std::string, FCLObject> collision_detection::CollisionWorldFCL::fcl_objs_
protected

Definition at line 86 of file collision_world_fcl.h.

std::unique_ptr<fcl::BroadPhaseCollisionManager> collision_detection::CollisionWorldFCL::manager_
protected

Definition at line 85 of file collision_world_fcl.h.

World::ObserverHandle collision_detection::CollisionWorldFCL::observer_handle_
private

Definition at line 91 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 Sun Oct 18 2020 13:16:34