Public Member Functions | List of all members
collision_detection::CollisionEnvAllValid Class Reference

Collision environment which always just returns no collisions. More...

#include <collision_env_allvalid.h>

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

Public Member Functions

void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
 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...
 
void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const override
 Check whether the robot model is in collision with the world. Allowed collisions are ignored. Self collisions are not checked. More...
 
void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2) const override
 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...
 
void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix &acm) const override
 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...
 
void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
 Check for robot self collision. Any collision between any pair of links is checked for, NO collisions are ignored. More...
 
void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const override
 Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
 CollisionEnvAllValid (const CollisionEnv &other, const WorldPtr &world)
 
 CollisionEnvAllValid (const moveit::core::RobotModelConstPtr &robot_model, const WorldPtr &world, double padding=0.0, double scale=1.0)
 
 CollisionEnvAllValid (const moveit::core::RobotModelConstPtr &robot_model, double padding=0.0, double scale=1.0)
 
void distanceRobot (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
 Compute the distance between a robot and the world. More...
 
virtual double distanceRobot (const moveit::core::RobotState &state) const
 
virtual double distanceRobot (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const
 
void distanceSelf (const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
 The distance to self-collision given the robot is at state state. More...
 
- Public Member Functions inherited from collision_detection::CollisionEnv
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...
 
 CollisionEnv ()=delete
 
 CollisionEnv (const CollisionEnv &other, const WorldPtr &world)
 Copy constructor. More...
 
 CollisionEnv (const moveit::core::RobotModelConstPtr &model, const WorldPtr &world, double padding=0.0, double scale=1.0)
 Constructor. More...
 
 CollisionEnv (const moveit::core::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
 Constructor. 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...
 
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. More...
 
const std::map< std::string, double > & getLinkPadding () const
 Get the link paddings as a map (from link names to padding value) More...
 
double getLinkPadding (const std::string &link_name) const
 Get the link padding 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...
 
double getLinkScale (const std::string &link_name) const
 Set the scaling for a particular link. More...
 
void getPadding (std::vector< moveit_msgs::LinkPadding > &padding) const
 Get the link padding as a vector of messages. More...
 
const moveit::core::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...
 
const WorldPtr & getWorld ()
 
const WorldConstPtr & getWorld () const
 
void setLinkPadding (const std::map< std::string, double > &padding)
 Set the link paddings using a map (from link names to padding value) More...
 
void setLinkPadding (const std::string &link_name, double padding)
 Set the link padding 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 setLinkScale (const std::string &link_name, double scale)
 Set the scaling for a particular link. More...
 
void setPadding (const std::vector< moveit_msgs::LinkPadding > &padding)
 Set the link padding from a vector of messages. More...
 
void setPadding (double padding)
 Set the link padding (for every link) More...
 
void setScale (const std::vector< moveit_msgs::LinkScale > &scale)
 Set the link scaling from a vector of messages. More...
 
void setScale (double scale)
 Set the link scaling (for every link) More...
 
virtual void setWorld (const WorldPtr &world)
 
virtual ~CollisionEnv ()
 

Additional Inherited Members

- Public Types inherited from collision_detection::CollisionEnv
using ObjectConstPtr = World::ObjectConstPtr
 
using ObjectPtr = World::ObjectPtr
 
- Protected Member Functions inherited from collision_detection::CollisionEnv
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 inherited from collision_detection::CollisionEnv
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...
 
moveit::core::RobotModelConstPtr robot_model_
 The kinematic model corresponding to this collision model. More...
 

Detailed Description

Collision environment which always just returns no collisions.

This can be used to save resources if collision checking is not important.

Definition at line 78 of file collision_env_allvalid.h.

Constructor & Destructor Documentation

◆ CollisionEnvAllValid() [1/3]

collision_detection::CollisionEnvAllValid::CollisionEnvAllValid ( const moveit::core::RobotModelConstPtr &  robot_model,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 79 of file collision_env_allvalid.cpp.

◆ CollisionEnvAllValid() [2/3]

collision_detection::CollisionEnvAllValid::CollisionEnvAllValid ( const moveit::core::RobotModelConstPtr &  robot_model,
const WorldPtr &  world,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 85 of file collision_env_allvalid.cpp.

◆ CollisionEnvAllValid() [3/3]

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

Definition at line 91 of file collision_env_allvalid.cpp.

Member Function Documentation

◆ checkRobotCollision() [1/4]

void collision_detection::CollisionEnvAllValid::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state 
) const
overridevirtual

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
robotThe collision model for the robot
stateThe kinematic state for which checks are being made

Implements collision_detection::CollisionEnv.

Definition at line 96 of file collision_env_allvalid.cpp.

◆ checkRobotCollision() [2/4]

void collision_detection::CollisionEnvAllValid::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
overridevirtual

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
robotThe collision model for the robot
stateThe kinematic state for which checks are being made
acmThe allowed collision matrix.

Implements collision_detection::CollisionEnv.

Definition at line 104 of file collision_env_allvalid.cpp.

◆ checkRobotCollision() [3/4]

void collision_detection::CollisionEnvAllValid::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2 
) const
overridevirtual

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
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::CollisionEnv.

Definition at line 113 of file collision_env_allvalid.cpp.

◆ checkRobotCollision() [4/4]

void collision_detection::CollisionEnvAllValid::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2,
const AllowedCollisionMatrix acm 
) const
overridevirtual

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
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::CollisionEnv.

Definition at line 122 of file collision_env_allvalid.cpp.

◆ checkSelfCollision() [1/2]

void collision_detection::CollisionEnvAllValid::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state 
) const
overridevirtual

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

Implements collision_detection::CollisionEnv.

Definition at line 149 of file collision_env_allvalid.cpp.

◆ checkSelfCollision() [2/2]

void collision_detection::CollisionEnvAllValid::checkSelfCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
overridevirtual

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::CollisionEnv.

Definition at line 157 of file collision_env_allvalid.cpp.

◆ distanceRobot() [1/3]

void collision_detection::CollisionEnvAllValid::distanceRobot ( const DistanceRequest req,
DistanceResult res,
const moveit::core::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
stateThe state for the robot to check distances from

Implements collision_detection::CollisionEnv.

Definition at line 132 of file collision_env_allvalid.cpp.

◆ distanceRobot() [2/3]

double collision_detection::CollisionEnvAllValid::distanceRobot ( const moveit::core::RobotState state) const
virtual

Definition at line 138 of file collision_env_allvalid.cpp.

◆ distanceRobot() [3/3]

double collision_detection::CollisionEnvAllValid::distanceRobot ( const moveit::core::RobotState state,
const AllowedCollisionMatrix acm 
) const
virtual

Definition at line 143 of file collision_env_allvalid.cpp.

◆ distanceSelf()

void collision_detection::CollisionEnvAllValid::distanceSelf ( const DistanceRequest req,
DistanceResult res,
const moveit::core::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::CollisionEnv.

Definition at line 166 of file collision_env_allvalid.cpp.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Apr 27 2024 02:25:26