Public Member Functions | Protected Member Functions | Protected Attributes | Friends
collision_detection::CollisionRobotFCL Class Reference

#include <collision_robot_fcl.h>

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

List of all members.

Public Member Functions

virtual void checkOtherCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
 Check for collision with a different robot (possibly a different kinematic model as well). Any collision between any pair of links is checked for, NO collisions are ignored.
virtual void checkOtherCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const
 Check for collision with a different robot (possibly a different kinematic model as well). Allowed collisions specified by the allowed collision matrix are taken into account.
virtual void checkOtherCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2) const
 Check for collision with a different robot (possibly a different kinematic model as well), in a continuous fashion. Any collision between any pair of links is checked for, NO collisions are ignored.
virtual void checkOtherCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2, const AllowedCollisionMatrix &acm) const
 Check for collision with a different robot (possibly a different kinematic model as well), in a continuous fashion. Allowed collisions specified by the allowed collision matrix are taken into account.
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const
 Check for self collision. Any collision between any pair of links is checked for, NO collisions are ignored.
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account.
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
 Check for self collision in a continuous manner. Any collision between any pair of links is checked for, NO collisions are ignored.
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
 Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account.
 CollisionRobotFCL (const robot_model::RobotModelConstPtr &kmodel, double padding=0.0, double scale=1.0)
 CollisionRobotFCL (const CollisionRobotFCL &other)
virtual double distanceOther (const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
 The distance to another robot instance.
virtual double distanceOther (const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const
 The distance to another robot instance, ignoring distances between links that are allowed to always collide.
virtual double distanceSelf (const robot_state::RobotState &state) const
 The distance to self-collision given the robot is at state state.
virtual double distanceSelf (const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 The distance to self-collision given the robot is at state state, ignoring the distances between links that are allowed to always collide (as specified by acm)

Protected Member Functions

void allocSelfCollisionBroadPhase (const robot_state::RobotState &state, FCLManager &manager) const
void checkOtherCollisionHelper (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix *acm) const
void checkSelfCollisionHelper (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
void constructFCLObject (const robot_state::RobotState &state, FCLObject &fcl_obj) const
double distanceOtherHelper (const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix *acm) const
double distanceSelfHelper (const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
void getAttachedBodyObjects (const robot_state::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
virtual void updatedPaddingOrScaling (const std::vector< std::string > &links)
 When the scale or padding is changed for a set of links by any of the functions in this class, updatedPaddingOrScaling() function is called. This function has an empty default implementation. The intention is to override this function in a derived class to allow for updating additional structures that may need such updating when link scale or padding changes.

Protected Attributes

std::vector< FCLGeometryConstPtrgeoms_

Friends

class CollisionWorldFCL

Detailed Description

Definition at line 45 of file collision_robot_fcl.h.


Constructor & Destructor Documentation

collision_detection::CollisionRobotFCL::CollisionRobotFCL ( const robot_model::RobotModelConstPtr &  kmodel,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 39 of file collision_robot_fcl.cpp.

Definition at line 56 of file collision_robot_fcl.cpp.


Member Function Documentation

Definition at line 104 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkOtherCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state 
) const [virtual]

Check for collision with a different robot (possibly a different kinematic model as well). 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.
other_robotThe collision representation for the other robot
other_stateThe kinematic state corresponding to the other robot

Implements collision_detection::CollisionRobot.

Definition at line 147 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkOtherCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state,
const AllowedCollisionMatrix acm 
) const [virtual]

Check for collision with a different robot (possibly a different kinematic model as well). 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.
other_robotThe collision representation for the other robot
other_stateThe kinematic state corresponding to the other robot
acmThe allowed collision matrix.

Implements collision_detection::CollisionRobot.

Definition at line 153 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkOtherCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state1,
const robot_state::RobotState state2,
const CollisionRobot other_robot,
const robot_state::RobotState other_state1,
const robot_state::RobotState other_state2 
) const [virtual]

Check for collision with a different robot (possibly a different kinematic model as well), in a continuous fashion. 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 (this robot)
state2The kinematic state at the end of the segment for which checks are being made (this robot)
other_robotThe collision representation for the other robot
other_state1The kinematic state at the start of the segment for which checks are being made (other robot)
other_state2The kinematic state at the end of the segment for which checks are being made (other robot)

Implements collision_detection::CollisionRobot.

Definition at line 160 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkOtherCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state1,
const robot_state::RobotState state2,
const CollisionRobot other_robot,
const robot_state::RobotState other_state1,
const robot_state::RobotState other_state2,
const AllowedCollisionMatrix acm 
) const [virtual]

Check for collision with a different robot (possibly a different kinematic model as well), in a continuous fashion. 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 (this robot)
state2The kinematic state at the end of the segment for which checks are being made (this robot)
other_robotThe collision representation for the other robot
other_state1The kinematic state at the start of the segment for which checks are being made (other robot)
other_state2The kinematic state at the end of the segment for which checks are being made (other robot)
acmThe allowed collision matrix.

Implements collision_detection::CollisionRobot.

Definition at line 166 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkOtherCollisionHelper ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state,
const AllowedCollisionMatrix acm 
) const [protected]

Definition at line 173 of file collision_robot_fcl.cpp.

Check for self collision. 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

Implements collision_detection::CollisionRobot.

Definition at line 114 of file collision_robot_fcl.cpp.

Check for self collision. 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.

Implements collision_detection::CollisionRobot.

Definition at line 119 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state1,
const robot_state::RobotState state2 
) const [virtual]

Check for self collision in a continuous manner. 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

Implements collision_detection::CollisionRobot.

Definition at line 125 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state1,
const robot_state::RobotState state2,
const AllowedCollisionMatrix acm 
) const [virtual]

Check for self collision. 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.

Implements collision_detection::CollisionRobot.

Definition at line 130 of file collision_robot_fcl.cpp.

Definition at line 135 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::constructFCLObject ( const robot_state::RobotState state,
FCLObject fcl_obj 
) const [protected]

Definition at line 72 of file collision_robot_fcl.cpp.

double collision_detection::CollisionRobotFCL::distanceOther ( const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state 
) const [virtual]

The distance to another robot instance.

Parameters:
stateThe state of this robot to consider
other_robotThe other robot instance to measure distance to
other_stateThe state of the other robot

Implements collision_detection::CollisionRobot.

Definition at line 238 of file collision_robot_fcl.cpp.

double collision_detection::CollisionRobotFCL::distanceOther ( const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state,
const AllowedCollisionMatrix acm 
) const [virtual]

The distance to another robot instance, ignoring distances between links that are allowed to always collide.

Parameters:
stateThe state of this robot to consider
other_robotThe other robot instance to measure distance to
other_stateThe state of the other robot
acmThe collision matrix specifying which links are allowed to always collide

Implements collision_detection::CollisionRobot.

Definition at line 245 of file collision_robot_fcl.cpp.

double collision_detection::CollisionRobotFCL::distanceOtherHelper ( const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state,
const AllowedCollisionMatrix acm 
) const [protected]

Definition at line 253 of file collision_robot_fcl.cpp.

The distance to self-collision given the robot is at state state.

Implements collision_detection::CollisionRobot.

Definition at line 211 of file collision_robot_fcl.cpp.

The distance to self-collision given the robot is at state state, ignoring the distances between links that are allowed to always collide (as specified by acm)

Implements collision_detection::CollisionRobot.

Definition at line 216 of file collision_robot_fcl.cpp.

Definition at line 222 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::getAttachedBodyObjects ( const robot_state::AttachedBody ab,
std::vector< FCLGeometryConstPtr > &  geoms 
) const [protected]

Definition at line 61 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::updatedPaddingOrScaling ( const std::vector< std::string > &  links) [protected, virtual]

When the scale or padding is changed for a set of links by any of the functions in this class, updatedPaddingOrScaling() function is called. This function has an empty default implementation. The intention is to override this function in a derived class to allow for updating additional structures that may need such updating when link scale or padding changes.

Parameters:
linksthe names of the links whose padding or scaling were updated

Reimplemented from collision_detection::CollisionRobot.

Definition at line 192 of file collision_robot_fcl.cpp.


Friends And Related Function Documentation

friend class CollisionWorldFCL [friend]

Definition at line 47 of file collision_robot_fcl.h.


Member Data Documentation

Definition at line 94 of file collision_robot_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 Thu Aug 27 2015 13:58:53