Public Member Functions | Protected Member Functions | Protected Attributes
collision_detection::CollisionRobot Class Reference

This class represents a collision model of the robot and can be used for self collision checks (to check if the robot is in collision with itself) or in collision checks with a different robot. Collision checks with the environment are performed using the CollisionWorld class. More...

#include <collision_robot.h>

Inheritance diagram for collision_detection::CollisionRobot:
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 =0
 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 =0
 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 =0
 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 =0
 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 =0
 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 =0
 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 =0
 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 =0
 Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account.
 CollisionRobot (const robot_model::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
 Constructor.
 CollisionRobot (const CollisionRobot &other)
 A copy constructor.
virtual double distanceOther (const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const =0
 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 =0
 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 =0
 The distance to self-collision given the robot is at state state.
virtual double distanceSelf (const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const =0
 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)
double getLinkPadding (const std::string &link_name) const
 Get the link padding for a particular link.
const std::map< std::string,
double > & 
getLinkPadding () const
 Get the link paddings as a map (from link names to padding value)
double getLinkScale (const std::string &link_name) const
 Set the scaling for a particular link.
const std::map< std::string,
double > & 
getLinkScale () const
 Get the link scaling as a map (from link names to scale value)
void getPadding (std::vector< moveit_msgs::LinkPadding > &padding) const
 Get the link padding as a vector of messages.
const
robot_model::RobotModelConstPtr & 
getRobotModel () const
 The kinematic model corresponding to this collision model.
void getScale (std::vector< moveit_msgs::LinkScale > &scale) const
 Get the link scaling as a vector of messages.
void setLinkPadding (const std::string &link_name, double padding)
 Set the link padding for a particular link.
void setLinkPadding (const std::map< std::string, double > &padding)
 Set the link paddings using a map (from link names to padding value)
void setLinkScale (const std::string &link_name, double scale)
 Set the scaling for a particular link.
void setLinkScale (const std::map< std::string, double > &scale)
 Set the link scaling using a map (from link names to scale value)
void setPadding (double padding)
 Set the link padding (for every link)
void setPadding (const std::vector< moveit_msgs::LinkPadding > &padding)
 Set the link padding from a vector of messages.
void setScale (double scale)
 Set the link scaling (for every link)
void setScale (const std::vector< moveit_msgs::LinkScale > &scale)
 Set the link scaling from a vector of messages.
virtual ~CollisionRobot ()

Protected Member Functions

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::map< std::string, double > link_padding_
 The internally maintained map (from link names to padding)
std::map< std::string, double > link_scale_
 The internally maintained map (from link names to scaling)
robot_model::RobotModelConstPtr robot_model_
 The kinematic model corresponding to this collision model.

Detailed Description

This class represents a collision model of the robot and can be used for self collision checks (to check if the robot is in collision with itself) or in collision checks with a different robot. Collision checks with the environment are performed using the CollisionWorld class.

Definition at line 54 of file collision_robot.h.


Constructor & Destructor Documentation

collision_detection::CollisionRobot::CollisionRobot ( const robot_model::RobotModelConstPtr &  model,
double  padding = 0.0,
double  scale = 1.0 
)

Constructor.

Parameters:
modelA robot model to construct the collision robot from
paddingThe padding to use for all objects/links on the robot scale A common scaling to use for all objects/links on the robot

Definition at line 70 of file collision_robot.cpp.

A copy constructor.

Definition at line 87 of file collision_robot.cpp.

Definition at line 67 of file collision_robot.h.


Member Function Documentation

virtual void collision_detection::CollisionRobot::checkOtherCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state 
) const [pure 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

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual void collision_detection::CollisionRobot::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 [pure 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.

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual void collision_detection::CollisionRobot::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 [pure 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)

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual void collision_detection::CollisionRobot::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 [pure 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.

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual void collision_detection::CollisionRobot::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state 
) const [pure 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

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual void collision_detection::CollisionRobot::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const [pure 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.

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual void collision_detection::CollisionRobot::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state1,
const robot_state::RobotState state2 
) const [pure 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

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual void collision_detection::CollisionRobot::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const robot_state::RobotState state1,
const robot_state::RobotState state2,
const AllowedCollisionMatrix acm 
) const [pure 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.

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual double collision_detection::CollisionRobot::distanceOther ( const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state 
) const [pure 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

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual double collision_detection::CollisionRobot::distanceOther ( const robot_state::RobotState state,
const CollisionRobot other_robot,
const robot_state::RobotState other_state,
const AllowedCollisionMatrix acm 
) const [pure 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

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual double collision_detection::CollisionRobot::distanceSelf ( const robot_state::RobotState state) const [pure virtual]

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

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

virtual double collision_detection::CollisionRobot::distanceSelf ( const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const [pure virtual]

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)

Implemented in collision_detection::CollisionRobotFCL, and collision_detection::CollisionRobotAllValid.

double collision_detection::CollisionRobot::getLinkPadding ( const std::string &  link_name) const

Get the link padding for a particular link.

Definition at line 136 of file collision_robot.cpp.

const std::map< std::string, double > & collision_detection::CollisionRobot::getLinkPadding ( ) const

Get the link paddings as a map (from link names to padding value)

Definition at line 159 of file collision_robot.cpp.

double collision_detection::CollisionRobot::getLinkScale ( const std::string &  link_name) const

Set the scaling for a particular link.

Definition at line 175 of file collision_robot.cpp.

const std::map< std::string, double > & collision_detection::CollisionRobot::getLinkScale ( ) const

Get the link scaling as a map (from link names to scale value)

Definition at line 198 of file collision_robot.cpp.

void collision_detection::CollisionRobot::getPadding ( std::vector< moveit_msgs::LinkPadding > &  padding) const

Get the link padding as a vector of messages.

Definition at line 231 of file collision_robot.cpp.

const robot_model::RobotModelConstPtr& collision_detection::CollisionRobot::getRobotModel ( ) const [inline]

The kinematic model corresponding to this collision model.

Definition at line 189 of file collision_robot.h.

void collision_detection::CollisionRobot::getScale ( std::vector< moveit_msgs::LinkScale > &  scale) const

Get the link scaling as a vector of messages.

Definition at line 243 of file collision_robot.cpp.

void collision_detection::CollisionRobot::setLinkPadding ( const std::string &  link_name,
double  padding 
)

Set the link padding for a particular link.

Parameters:
link_nameThe link name to set padding for
paddingThe padding to set (in meters)

Definition at line 125 of file collision_robot.cpp.

void collision_detection::CollisionRobot::setLinkPadding ( const std::map< std::string, double > &  padding)

Set the link paddings using a map (from link names to padding value)

Definition at line 145 of file collision_robot.cpp.

void collision_detection::CollisionRobot::setLinkScale ( const std::string &  link_name,
double  scale 
)

Set the scaling for a particular link.

Definition at line 164 of file collision_robot.cpp.

void collision_detection::CollisionRobot::setLinkScale ( const std::map< std::string, double > &  scale)

Set the link scaling using a map (from link names to scale value)

Definition at line 184 of file collision_robot.cpp.

Set the link padding (for every link)

Definition at line 93 of file collision_robot.cpp.

void collision_detection::CollisionRobot::setPadding ( const std::vector< moveit_msgs::LinkPadding > &  padding)

Set the link padding from a vector of messages.

Definition at line 203 of file collision_robot.cpp.

Set the link scaling (for every link)

Definition at line 109 of file collision_robot.cpp.

void collision_detection::CollisionRobot::setScale ( const std::vector< moveit_msgs::LinkScale > &  scale)

Set the link scaling from a vector of messages.

Definition at line 217 of file collision_robot.cpp.

void collision_detection::CollisionRobot::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 in collision_detection::CollisionRobotFCL.

Definition at line 255 of file collision_robot.cpp.


Member Data Documentation

std::map<std::string, double> collision_detection::CollisionRobot::link_padding_ [protected]

The internally maintained map (from link names to padding)

Definition at line 252 of file collision_robot.h.

std::map<std::string, double> collision_detection::CollisionRobot::link_scale_ [protected]

The internally maintained map (from link names to scaling)

Definition at line 255 of file collision_robot.h.

robot_model::RobotModelConstPtr collision_detection::CollisionRobot::robot_model_ [protected]

The kinematic model corresponding to this collision model.

Definition at line 249 of file collision_robot.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jun 19 2019 19:23:49