moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
collision_detection::CollisionEnv Class Referenceabstract

Provides the interface to the individual collision checking libraries. More...

#include <collision_env.h>

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

Public Types

using ObjectPtr = World::ObjectPtr
 
using ObjectConstPtr = World::ObjectConstPtr
 

Public Member Functions

 CollisionEnv ()=delete
 
 CollisionEnv (const moveit::core::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
 Constructor. More...
 
 CollisionEnv (const moveit::core::RobotModelConstPtr &model, const WorldPtr &world, double padding=0.0, double scale=1.0)
 Constructor. More...
 
 CollisionEnv (const CollisionEnv &other, const WorldPtr &world)
 Copy constructor. More...
 
virtual ~CollisionEnv ()
 
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const =0
 Check for robot 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 moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const =0
 Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
virtual void checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::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 moveit::core::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 checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const =0
 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 moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const =0
 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 moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix &acm) const =0
 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 checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2) const =0
 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 distanceSelf (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const =0
 The distance to self-collision given the robot is at state state. More...
 
double distanceSelf (const moveit::core::RobotState &state) const
 The distance to self-collision given the robot is at state state. More...
 
double distanceSelf (const moveit::core::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...
 
virtual void distanceRobot (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const =0
 Compute the distance between a robot and the world. More...
 
double distanceRobot (const moveit::core::RobotState &state, bool verbose=false) const
 Compute the shortest distance between a robot and the world. More...
 
double distanceRobot (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const
 Compute the shortest distance between a robot and the world. More...
 
virtual void setWorld (const WorldPtr &world)
 
const WorldPtr & getWorld ()
 
const WorldConstPtr & getWorld () const
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 The kinematic model corresponding to this collision model. More...
 
void setLinkPadding (const std::string &link_name, double padding)
 Set the link padding for a particular link. More...
 
double getLinkPadding (const std::string &link_name) const
 Get 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...
 
const std::map< std::string, double > & getLinkPadding () const
 Get the link paddings as 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...
 
double getLinkScale (const std::string &link_name) const
 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...
 
const std::map< std::string, double > & getLinkScale () const
 Get the link scaling as a map (from link names to scale value) More...
 
void setPadding (double padding)
 Set the link padding (for every link) More...
 
void setScale (double scale)
 Set the link scaling (for every link) More...
 
void setPadding (const std::vector< moveit_msgs::msg::LinkPadding > &padding)
 Set the link padding from a vector of messages. More...
 
void getPadding (std::vector< moveit_msgs::msg::LinkPadding > &padding) const
 Get the link padding as a vector of messages. More...
 
void setScale (const std::vector< moveit_msgs::msg::LinkScale > &scale)
 Set the link scaling from a vector of messages. More...
 
void getScale (std::vector< moveit_msgs::msg::LinkScale > &scale) const
 Get the link scaling as a vector of messages. More...
 

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

Protected Attributes

moveit::core::RobotModelConstPtr robot_model_
 The kinematic model corresponding to this collision model. More...
 
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...
 

Detailed Description

Provides the interface to the individual collision checking libraries.

Definition at line 51 of file collision_env.h.

Member Typedef Documentation

◆ ObjectConstPtr

Definition at line 252 of file collision_env.h.

◆ ObjectPtr

Definition at line 251 of file collision_env.h.

Constructor & Destructor Documentation

◆ CollisionEnv() [1/4]

collision_detection::CollisionEnv::CollisionEnv ( )
delete

◆ CollisionEnv() [2/4]

collision_detection::CollisionEnv::CollisionEnv ( const moveit::core::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 scale A common scaling to use for all objects/links on the robot

Definition at line 77 of file collision_env.cpp.

◆ CollisionEnv() [3/4]

collision_detection::CollisionEnv::CollisionEnv ( const moveit::core::RobotModelConstPtr &  model,
const WorldPtr &  world,
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 scale A common scaling to use for all objects/links on the robot

Definition at line 93 of file collision_env.cpp.

◆ CollisionEnv() [4/4]

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

Copy constructor.

Definition at line 110 of file collision_env.cpp.

◆ ~CollisionEnv()

virtual collision_detection::CollisionEnv::~CollisionEnv ( )
inlinevirtual

Definition at line 74 of file collision_env.h.

Member Function Documentation

◆ checkCollision() [1/2]

void collision_detection::CollisionEnv::checkCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state 
) const
virtual

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.

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

Reimplemented in collision_detection::CollisionEnvDistanceField.

Definition at line 296 of file collision_env.cpp.

Here is the call graph for this function:

◆ checkCollision() [2/2]

void collision_detection::CollisionEnv::checkCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
virtual

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.

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.

Reimplemented in collision_detection::CollisionEnvDistanceField.

Definition at line 304 of file collision_env.cpp.

Here is the call graph for this function:

◆ checkRobotCollision() [1/4]

virtual void collision_detection::CollisionEnv::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state 
) const
pure 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 robot The collision model for the robot
stateThe kinematic state for which checks are being made

Implemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvAllValid.

Here is the caller graph for this function:

◆ checkRobotCollision() [2/4]

virtual void collision_detection::CollisionEnv::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
pure 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 robot The collision model for the robot
stateThe kinematic state for which checks are being made
acmThe allowed collision matrix.

Implemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvAllValid.

◆ checkRobotCollision() [3/4]

virtual void collision_detection::CollisionEnv::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2 
) const
pure 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 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.

Implemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvAllValid.

◆ checkRobotCollision() [4/4]

virtual void collision_detection::CollisionEnv::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2,
const AllowedCollisionMatrix acm 
) const
pure 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 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.

Implemented in collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvAllValid.

◆ checkSelfCollision() [1/2]

virtual void collision_detection::CollisionEnv::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state 
) const
pure virtual

Check for robot 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::CollisionEnvFCL, collision_detection::CollisionEnvBullet, collision_detection::CollisionEnvAllValid, and collision_detection::CollisionEnvDistanceField.

Here is the caller graph for this function:

◆ checkSelfCollision() [2/2]

virtual void collision_detection::CollisionEnv::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::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::CollisionEnvFCL, collision_detection::CollisionEnvBullet, collision_detection::CollisionEnvAllValid, and collision_detection::CollisionEnvDistanceField.

◆ distanceRobot() [1/3]

virtual void collision_detection::CollisionEnv::distanceRobot ( const DistanceRequest req,
DistanceResult res,
const moveit::core::RobotState state 
) const
pure virtual

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

Implemented in collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, collision_detection::CollisionEnvAllValid, and collision_detection::CollisionEnvDistanceField.

Here is the caller graph for this function:

◆ distanceRobot() [2/3]

double collision_detection::CollisionEnv::distanceRobot ( const moveit::core::RobotState state,
bool  verbose = false 
) const
inline

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
verboseOutput debug information about distance checks

Definition at line 202 of file collision_env.h.

Here is the call graph for this function:

◆ distanceRobot() [3/3]

double collision_detection::CollisionEnv::distanceRobot ( const moveit::core::RobotState state,
const AllowedCollisionMatrix acm,
bool  verbose = false 
) const
inline

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.
verboseOutput debug information about distance checks

Definition at line 220 of file collision_env.h.

Here is the call graph for this function:

◆ distanceSelf() [1/3]

virtual void collision_detection::CollisionEnv::distanceSelf ( const DistanceRequest req,
DistanceResult res,
const moveit::core::RobotState state 
) const
pure virtual

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

Implemented in collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, collision_detection::CollisionEnvAllValid, and collision_detection::CollisionEnvDistanceField.

Here is the caller graph for this function:

◆ distanceSelf() [2/3]

double collision_detection::CollisionEnv::distanceSelf ( const moveit::core::RobotState state) const
inline

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

Definition at line 167 of file collision_env.h.

Here is the call graph for this function:

◆ distanceSelf() [3/3]

double collision_detection::CollisionEnv::distanceSelf ( const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
inline

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)

Definition at line 179 of file collision_env.h.

Here is the call graph for this function:

◆ getLinkPadding() [1/2]

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

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

Definition at line 184 of file collision_env.cpp.

Here is the caller graph for this function:

◆ getLinkPadding() [2/2]

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

Get the link padding for a particular link.

Definition at line 160 of file collision_env.cpp.

◆ getLinkScale() [1/2]

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

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

Definition at line 224 of file collision_env.cpp.

Here is the caller graph for this function:

◆ getLinkScale() [2/2]

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

Set the scaling for a particular link.

Definition at line 201 of file collision_env.cpp.

◆ getPadding()

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

Get the link padding as a vector of messages.

Definition at line 259 of file collision_env.cpp.

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& collision_detection::CollisionEnv::getRobotModel ( ) const
inline

The kinematic model corresponding to this collision model.

Definition at line 255 of file collision_env.h.

Here is the caller graph for this function:

◆ getScale()

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

Get the link scaling as a vector of messages.

Definition at line 271 of file collision_env.cpp.

◆ getWorld() [1/2]

const WorldPtr& collision_detection::CollisionEnv::getWorld ( )
inline

access the world geometry

Definition at line 240 of file collision_env.h.

Here is the caller graph for this function:

◆ getWorld() [2/2]

const WorldConstPtr& collision_detection::CollisionEnv::getWorld ( ) const
inline

access the world geometry

Definition at line 246 of file collision_env.h.

◆ setLinkPadding() [1/2]

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

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

Definition at line 169 of file collision_env.cpp.

◆ setLinkPadding() [2/2]

void collision_detection::CollisionEnv::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 148 of file collision_env.cpp.

◆ setLinkScale() [1/2]

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

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

Definition at line 210 of file collision_env.cpp.

Here is the call graph for this function:

◆ setLinkScale() [2/2]

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

Set the scaling for a particular link.

Definition at line 189 of file collision_env.cpp.

◆ setPadding() [1/2]

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

Set the link padding from a vector of messages.

Definition at line 229 of file collision_env.cpp.

◆ setPadding() [2/2]

void collision_detection::CollisionEnv::setPadding ( double  padding)

Set the link padding (for every link)

Definition at line 116 of file collision_env.cpp.

Here is the caller graph for this function:

◆ setScale() [1/2]

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

Set the link scaling from a vector of messages.

Definition at line 244 of file collision_env.cpp.

◆ setScale() [2/2]

void collision_detection::CollisionEnv::setScale ( double  scale)

Set the link scaling (for every link)

Definition at line 132 of file collision_env.cpp.

◆ setWorld()

void collision_detection::CollisionEnv::setWorld ( const WorldPtr &  world)
virtual

set the world to use. This can be expensive unless the new and old world are empty. Passing nullptr will result in a new empty world being created.

Reimplemented in collision_detection::CollisionEnvHybrid, collision_detection::CollisionEnvDistanceField, collision_detection::CollisionEnvFCL, and collision_detection::CollisionEnvBullet.

Definition at line 287 of file collision_env.cpp.

Here is the caller graph for this function:

◆ updatedPaddingOrScaling()

void collision_detection::CollisionEnv::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 in collision_detection::CollisionEnvFCL, collision_detection::CollisionEnvBullet, and collision_detection::CollisionEnvDistanceField.

Definition at line 283 of file collision_env.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ link_padding_

std::map<std::string, double> collision_detection::CollisionEnv::link_padding_
protected

The internally maintained map (from link names to padding)

Definition at line 318 of file collision_env.h.

◆ link_scale_

std::map<std::string, double> collision_detection::CollisionEnv::link_scale_
protected

The internally maintained map (from link names to scaling)

Definition at line 321 of file collision_env.h.

◆ robot_model_

moveit::core::RobotModelConstPtr collision_detection::CollisionEnv::robot_model_
protected

The kinematic model corresponding to this collision model.

Definition at line 315 of file collision_env.h.


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