Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
collision_detection::CollisionRobotFCL Class Reference

#include <collision_robot_fcl.h>

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

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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
 CollisionRobotFCL (const robot_model::RobotModelConstPtr &kmodel, double padding=0.0, double scale=1.0)
 
 CollisionRobotFCL (const CollisionRobotFCL &other)
 
virtual void distanceOther (const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const override
 The distance to self-collision given the robot is at state state. More...
 
virtual void distanceSelf (const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const override
 The distance to self-collision given the robot is at state state. More...
 
- Public Member Functions inherited from collision_detection::CollisionRobot
 CollisionRobot (const robot_model::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
 Constructor. More...
 
 CollisionRobot (const CollisionRobot &other)
 A copy constructor. More...
 
double distanceOther (const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
 The distance to another robot instance. More...
 
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. More...
 
double distanceSelf (const robot_state::RobotState &state) const
 The distance to self-collision given the robot is at state state. More...
 
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) More...
 
double getLinkPadding (const std::string &link_name) const
 Get the link padding for a particular link. More...
 
const std::map< std::string, double > & getLinkPadding () const
 Get the link paddings as a map (from link names to padding value) More...
 
double getLinkScale (const std::string &link_name) const
 Set the scaling for a particular link. More...
 
const std::map< std::string, double > & getLinkScale () const
 Get the link scaling as a map (from link names to scale value) More...
 
void getPadding (std::vector< moveit_msgs::LinkPadding > &padding) const
 Get the link padding as a vector of messages. More...
 
const robot_model::RobotModelConstPtr & getRobotModel () const
 The kinematic model corresponding to this collision model. More...
 
void getScale (std::vector< moveit_msgs::LinkScale > &scale) const
 Get the link scaling as a vector of messages. More...
 
void setLinkPadding (const std::string &link_name, double padding)
 Set the link padding for a particular link. More...
 
void setLinkPadding (const std::map< std::string, double > &padding)
 Set the link paddings using a map (from link names to padding value) More...
 
void setLinkScale (const std::string &link_name, double scale)
 Set the scaling for a particular link. More...
 
void setLinkScale (const std::map< std::string, double > &scale)
 Set the link scaling using a map (from link names to scale value) More...
 
void setPadding (double padding)
 Set the link padding (for every link) More...
 
void setPadding (const std::vector< moveit_msgs::LinkPadding > &padding)
 Set the link padding from a vector of messages. More...
 
void setScale (double scale)
 Set the link scaling (for every link) More...
 
void setScale (const std::vector< moveit_msgs::LinkScale > &scale)
 Set the link scaling from a vector of messages. More...
 
virtual ~CollisionRobot ()
 

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
 
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. More...
 

Protected Attributes

std::vector< FCLCollisionObjectConstPtrfcl_objs_
 
std::vector< FCLGeometryConstPtr > geoms_
 
- Protected Attributes inherited from collision_detection::CollisionRobot
std::map< std::string, double > link_padding_
 The internally maintained map (from link names to padding) More...
 
std::map< std::string, double > link_scale_
 The internally maintained map (from link names to scaling) More...
 
robot_model::RobotModelConstPtr robot_model_
 The kinematic model corresponding to this collision model. More...
 

Friends

class CollisionWorldFCL
 

Detailed Description

Definition at line 44 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 41 of file collision_robot_fcl.cpp.

collision_detection::CollisionRobotFCL::CollisionRobotFCL ( const CollisionRobotFCL other)

Definition at line 71 of file collision_robot_fcl.cpp.

Member Function Documentation

void collision_detection::CollisionRobotFCL::allocSelfCollisionBroadPhase ( const robot_state::RobotState state,
FCLManager manager 
) const
protected

Definition at line 127 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 186 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 193 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 201 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 210 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 220 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state 
) const
virtual

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 137 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state,
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
stateThe kinematic state for which checks are being made
acmThe allowed collision matrix.

Implements collision_detection::CollisionRobot.

Definition at line 143 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 150 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 157 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::checkSelfCollisionHelper ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const
protected

Definition at line 164 of file collision_robot_fcl.cpp.

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

Definition at line 89 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::distanceOther ( const DistanceRequest req,
DistanceResult res,
const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state 
) const
overridevirtual

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

Parameters
reqA DistanceRequest object that encapsulates the distance request
resA DistanceResult object that encapsulates the distance result
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 286 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::distanceSelf ( const DistanceRequest req,
DistanceResult res,
const robot_state::RobotState state 
) const
overridevirtual

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

Parameters
reqA DistanceRequest object that encapsulates the distance request
resA DistanceResult object that encapsulates the distance result
stateThe state of this robot to consider

Implements collision_detection::CollisionRobot.

Definition at line 276 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 77 of file collision_robot_fcl.cpp.

void collision_detection::CollisionRobotFCL::updatedPaddingOrScaling ( const std::vector< std::string > &  links)
protectedvirtual

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 251 of file collision_robot_fcl.cpp.

Friends And Related Function Documentation

friend class CollisionWorldFCL
friend

Definition at line 46 of file collision_robot_fcl.h.

Member Data Documentation

std::vector<FCLCollisionObjectConstPtr> collision_detection::CollisionRobotFCL::fcl_objs_
protected

Definition at line 99 of file collision_robot_fcl.h.

std::vector<FCLGeometryConstPtr> collision_detection::CollisionRobotFCL::geoms_
protected

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