moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
collision_detection::CollisionEnvDistanceField Class Reference

#include <collision_env_distance_field.h>

Inheritance diagram for collision_detection::CollisionEnvDistanceField:
Inheritance graph
[legend]
Collaboration diagram for collision_detection::CollisionEnvDistanceField:
Collaboration graph
[legend]

Classes

struct  DistanceFieldCacheEntryWorld
 

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionEnvDistanceField (const moveit::core::RobotModelConstPtr &robot_model, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions=std::map< std::string, std::vector< CollisionSphere >>(), double size_x=DEFAULT_SIZE_X, double size_y=DEFAULT_SIZE_Y, double size_z=DEFAULT_SIZE_Z, const Eigen::Vector3d &origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE, double padding=0.0, double scale=1.0)
 
 CollisionEnvDistanceField (const moveit::core::RobotModelConstPtr &robot_model, const WorldPtr &world, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions=std::map< std::string, std::vector< CollisionSphere >>(), double size_x=DEFAULT_SIZE_X, double size_y=DEFAULT_SIZE_Y, double size_z=DEFAULT_SIZE_Z, const Eigen::Vector3d &origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE, double padding=0.0, double scale=1.0)
 
 CollisionEnvDistanceField (const CollisionEnvDistanceField &other, const WorldPtr &world)
 
void initialize (const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, const Eigen::Vector3d &size, const Eigen::Vector3d &origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance)
 
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::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 collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
 
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm) const override
 Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) const
 
void createCollisionModelMarker (const moveit::core::RobotState &state, visualization_msgs::msg::MarkerArray &model_markers) const
 
virtual double distanceSelf (const moveit::core::RobotState &) const
 
virtual double distanceSelf (const moveit::core::RobotState &, const collision_detection::AllowedCollisionMatrix &) const
 
void distanceSelf (const DistanceRequest &, DistanceResult &, const moveit::core::RobotState &) const override
 The distance to self-collision given the robot is at state state. More...
 
DistanceFieldCacheEntryConstPtr getLastDistanceFieldEntry () const
 
 MOVEIT_STRUCT_FORWARD (DistanceFieldCacheEntryWorld)
 
 ~CollisionEnvDistanceField () override
 
void checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
 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, GroupStateRepresentationPtr &gsr) const
 
void checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm) const override
 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 checkCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) const
 
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...
 
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
 
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...
 
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) const
 
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 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...
 
virtual double distanceRobot (const moveit::core::RobotState &state, bool verbose=false) const
 
virtual double distanceRobot (const moveit::core::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const
 
void distanceRobot (const DistanceRequest &, DistanceResult &, const moveit::core::RobotState &) const override
 Compute the distance between a robot and the world. More...
 
void setWorld (const WorldPtr &world) override
 
distance_field::DistanceFieldConstPtr getDistanceField () const
 
collision_detection::GroupStateRepresentationConstPtr getLastGroupStateRepresentation () const
 
void getCollisionGradients (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
 
void getAllCollisions (const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
 
- Public Member Functions inherited from collision_detection::CollisionEnv
 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 ()
 
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...
 
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...
 
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

bool getSelfProximityGradients (GroupStateRepresentationPtr &gsr) const
 
bool getIntraGroupProximityGradients (GroupStateRepresentationPtr &gsr) const
 
bool getSelfCollisions (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
 
bool getIntraGroupCollisions (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
 
void checkSelfCollisionHelper (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
 
void updateGroupStateRepresentationState (const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
 
void generateCollisionCheckingStructures (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr, bool generate_distance_field) const
 
DistanceFieldCacheEntryConstPtr getDistanceFieldCacheEntry (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm) const
 
DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, bool generate_distance_field) const
 
void addLinkBodyDecompositions (double resolution)
 
void addLinkBodyDecompositions (double resolution, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions)
 
PosedBodySphereDecompositionPtr getPosedLinkBodySphereDecomposition (const moveit::core::LinkModel *ls, unsigned int ind) const
 
PosedBodyPointDecompositionPtr getPosedLinkBodyPointDecomposition (const moveit::core::LinkModel *ls) const
 
void getGroupStateRepresentation (const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
 
bool compareCacheEntryToState (const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state) const
 
bool compareCacheEntryToAllowedCollisionMatrix (const DistanceFieldCacheEntryConstPtr &dfce, const collision_detection::AllowedCollisionMatrix &acm) const
 
void updatedPaddingOrScaling (const std::vector< std::string > &) override
 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...
 
DistanceFieldCacheEntryWorldPtr generateDistanceFieldCacheEntryWorld ()
 
void updateDistanceObject (const std::string &id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points)
 
bool getEnvironmentCollisions (const CollisionRequest &req, CollisionResult &res, const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
 
bool getEnvironmentProximityGradients (const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
 
void notifyObjectChange (const ObjectConstPtr &obj, World::Action action)
 

Protected Attributes

Eigen::Vector3d size_
 
Eigen::Vector3d origin_
 
bool use_signed_distance_field_
 
double resolution_
 
double collision_tolerance_
 
double max_propogation_distance_
 
std::vector< BodyDecompositionConstPtr > link_body_decomposition_vector_
 
std::map< std::string, unsigned int > link_body_decomposition_index_map_
 
std::mutex update_cache_lock_
 
DistanceFieldCacheEntryPtr distance_field_cache_entry_
 
std::map< std::string, std::map< std::string, bool > > in_group_update_map_
 
std::map< std::string, GroupStateRepresentationPtr > pregenerated_group_state_representation_map_
 
planning_scene::PlanningScenePtr planning_scene_
 
std::mutex update_cache_lock_world_
 
DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_
 
GroupStateRepresentationPtr last_gsr_
 
World::ObserverHandle observer_handle_
 
- Protected Attributes inherited from collision_detection::CollisionEnv
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...
 

Static Protected Attributes

static const rclcpp::Logger LOGGER
 

Additional Inherited Members

- Public Types inherited from collision_detection::CollisionEnv
using ObjectPtr = World::ObjectPtr
 
using ObjectConstPtr = World::ObjectConstPtr
 

Detailed Description

Definition at line 59 of file collision_env_distance_field.h.

Constructor & Destructor Documentation

◆ CollisionEnvDistanceField() [1/3]

collision_detection::CollisionEnvDistanceField::CollisionEnvDistanceField ( const moveit::core::RobotModelConstPtr &  robot_model,
const std::map< std::string, std::vector< CollisionSphere >> &  link_body_decompositions = std::map<std::string, std::vector<CollisionSphere>>(),
double  size_x = DEFAULT_SIZE_X,
double  size_y = DEFAULT_SIZE_Y,
double  size_z = DEFAULT_SIZE_Z,
const Eigen::Vector3d &  origin = Eigen::Vector3d(0, 0, 0),
bool  use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
double  resolution = DEFAULT_RESOLUTION,
double  collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
double  max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 60 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ CollisionEnvDistanceField() [2/3]

collision_detection::CollisionEnvDistanceField::CollisionEnvDistanceField ( const moveit::core::RobotModelConstPtr &  robot_model,
const WorldPtr &  world,
const std::map< std::string, std::vector< CollisionSphere >> &  link_body_decompositions = std::map<std::string, std::vector<CollisionSphere>>(),
double  size_x = DEFAULT_SIZE_X,
double  size_y = DEFAULT_SIZE_Y,
double  size_z = DEFAULT_SIZE_Z,
const Eigen::Vector3d &  origin = Eigen::Vector3d(0, 0, 0),
bool  use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
double  resolution = DEFAULT_RESOLUTION,
double  collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
double  max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 79 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ CollisionEnvDistanceField() [3/3]

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

Definition at line 98 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ ~CollisionEnvDistanceField()

collision_detection::CollisionEnvDistanceField::~CollisionEnvDistanceField ( )
override

Definition at line 121 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ addLinkBodyDecompositions() [1/2]

void collision_detection::CollisionEnvDistanceField::addLinkBodyDecompositions ( double  resolution)
protected

Definition at line 960 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ addLinkBodyDecompositions() [2/2]

void collision_detection::CollisionEnvDistanceField::addLinkBodyDecompositions ( double  resolution,
const std::map< std::string, std::vector< CollisionSphere >> &  link_body_decompositions 
)
protected

Definition at line 1049 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkCollision() [1/4]

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

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

Definition at line 1382 of file collision_env_distance_field.cpp.

Here is the caller graph for this function:

◆ checkCollision() [2/4]

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

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

Definition at line 1414 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkCollision() [3/4]

void collision_detection::CollisionEnvDistanceField::checkCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const
virtual

Definition at line 1422 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkCollision() [4/4]

void collision_detection::CollisionEnvDistanceField::checkCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
GroupStateRepresentationPtr &  gsr 
) const
virtual

Definition at line 1389 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkRobotCollision() [1/6]

void collision_detection::CollisionEnvDistanceField::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 @robot robot The collision model for the robot
stateThe kinematic state for which checks are being made

Implements collision_detection::CollisionEnv.

Definition at line 1447 of file collision_env_distance_field.cpp.

Here is the caller graph for this function:

◆ checkRobotCollision() [2/6]

void collision_detection::CollisionEnvDistanceField::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 @robot robot The 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 1473 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkRobotCollision() [3/6]

void collision_detection::CollisionEnvDistanceField::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const
virtual

Definition at line 1481 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkRobotCollision() [4/6]

void collision_detection::CollisionEnvDistanceField::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
GroupStateRepresentationPtr &  gsr 
) const
virtual

Definition at line 1454 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkRobotCollision() [5/6]

void collision_detection::CollisionEnvDistanceField::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 @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.

Implements collision_detection::CollisionEnv.

Definition at line 1510 of file collision_env_distance_field.cpp.

◆ checkRobotCollision() [6/6]

void collision_detection::CollisionEnvDistanceField::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 @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.

Implements collision_detection::CollisionEnv.

Definition at line 1502 of file collision_env_distance_field.cpp.

◆ checkSelfCollision() [1/4]

void collision_detection::CollisionEnvDistanceField::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::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 235 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkSelfCollision() [2/4]

void collision_detection::CollisionEnvDistanceField::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState state,
const collision_detection::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 251 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkSelfCollision() [3/4]

void collision_detection::CollisionEnvDistanceField::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState state,
const collision_detection::AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 260 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkSelfCollision() [4/4]

void collision_detection::CollisionEnvDistanceField::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState state,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 243 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ checkSelfCollisionHelper()

void collision_detection::CollisionEnvDistanceField::checkSelfCollisionHelper ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState state,
const collision_detection::AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const
protected

Definition at line 177 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ compareCacheEntryToAllowedCollisionMatrix()

bool collision_detection::CollisionEnvDistanceField::compareCacheEntryToAllowedCollisionMatrix ( const DistanceFieldCacheEntryConstPtr &  dfce,
const collision_detection::AllowedCollisionMatrix acm 
) const
protected

Definition at line 1314 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ compareCacheEntryToState()

bool collision_detection::CollisionEnvDistanceField::compareCacheEntryToState ( const DistanceFieldCacheEntryConstPtr &  dfce,
const moveit::core::RobotState state 
) const
protected

Definition at line 1254 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ createCollisionModelMarker()

void collision_detection::CollisionEnvDistanceField::createCollisionModelMarker ( const moveit::core::RobotState state,
visualization_msgs::msg::MarkerArray &  model_markers 
) const

Definition at line 981 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ distanceRobot() [1/3]

void collision_detection::CollisionEnvDistanceField::distanceRobot ( const DistanceRequest req,
DistanceResult res,
const moveit::core::RobotState state 
) const
inlineoverridevirtual

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

Implements collision_detection::CollisionEnv.

Definition at line 195 of file collision_env_distance_field.h.

◆ distanceRobot() [2/3]

virtual double collision_detection::CollisionEnvDistanceField::distanceRobot ( const moveit::core::RobotState state,
bool  verbose = false 
) const
inlinevirtual

Definition at line 179 of file collision_env_distance_field.h.

◆ distanceRobot() [3/3]

virtual double collision_detection::CollisionEnvDistanceField::distanceRobot ( const moveit::core::RobotState state,
const AllowedCollisionMatrix acm,
bool  verbose = false 
) const
inlinevirtual

Definition at line 186 of file collision_env_distance_field.h.

◆ distanceSelf() [1/3]

void collision_detection::CollisionEnvDistanceField::distanceSelf ( const DistanceRequest req,
DistanceResult res,
const moveit::core::RobotState state 
) const
inlineoverridevirtual

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 120 of file collision_env_distance_field.h.

◆ distanceSelf() [2/3]

virtual double collision_detection::CollisionEnvDistanceField::distanceSelf ( const moveit::core::RobotState ) const
inlinevirtual

Definition at line 109 of file collision_env_distance_field.h.

◆ distanceSelf() [3/3]

virtual double collision_detection::CollisionEnvDistanceField::distanceSelf ( const moveit::core::RobotState ,
const collision_detection::AllowedCollisionMatrix  
) const
inlinevirtual

Definition at line 114 of file collision_env_distance_field.h.

◆ generateCollisionCheckingStructures()

void collision_detection::CollisionEnvDistanceField::generateCollisionCheckingStructures ( const std::string &  group_name,
const moveit::core::RobotState state,
const collision_detection::AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr,
bool  generate_distance_field 
) const
protected

Definition at line 158 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ generateDistanceFieldCacheEntry()

DistanceFieldCacheEntryPtr collision_detection::CollisionEnvDistanceField::generateDistanceFieldCacheEntry ( const std::string &  group_name,
const moveit::core::RobotState state,
const collision_detection::AllowedCollisionMatrix acm,
bool  generate_distance_field 
) const
protected

Definition at line 710 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ generateDistanceFieldCacheEntryWorld()

CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr collision_detection::CollisionEnvDistanceField::generateDistanceFieldCacheEntryWorld ( )
protected

Definition at line 1782 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getAllCollisions()

void collision_detection::CollisionEnvDistanceField::getAllCollisions ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 1540 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ getCollisionGradients()

void collision_detection::CollisionEnvDistanceField::getCollisionGradients ( const CollisionRequest req,
CollisionResult res,
const moveit::core::RobotState state,
const AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 1517 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ getDistanceField()

distance_field::DistanceFieldConstPtr collision_detection::CollisionEnvDistanceField::getDistanceField ( ) const
inline

Definition at line 203 of file collision_env_distance_field.h.

◆ getDistanceFieldCacheEntry()

DistanceFieldCacheEntryConstPtr collision_detection::CollisionEnvDistanceField::getDistanceFieldCacheEntry ( const std::string &  group_name,
const moveit::core::RobotState state,
const collision_detection::AllowedCollisionMatrix acm 
) const
protected

Definition at line 203 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getEnvironmentCollisions()

bool collision_detection::CollisionEnvDistanceField::getEnvironmentCollisions ( const CollisionRequest req,
CollisionResult res,
const distance_field::DistanceFieldConstPtr &  env_distance_field,
GroupStateRepresentationPtr &  gsr 
) const
protected

Definition at line 1561 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getEnvironmentProximityGradients()

bool collision_detection::CollisionEnvDistanceField::getEnvironmentProximityGradients ( const distance_field::DistanceFieldConstPtr &  env_distance_field,
GroupStateRepresentationPtr &  gsr 
) const
protected

Definition at line 1645 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getGroupStateRepresentation()

void collision_detection::CollisionEnvDistanceField::getGroupStateRepresentation ( const DistanceFieldCacheEntryConstPtr &  dfce,
const moveit::core::RobotState state,
GroupStateRepresentationPtr &  gsr 
) const
protected

std::cerr << "Attached " << dfce->attached_body_names_[i] << " index " << dfce->attached_body_link_state_indices_[i] << '
';

Definition at line 1157 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getIntraGroupCollisions()

bool collision_detection::CollisionEnvDistanceField::getIntraGroupCollisions ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
GroupStateRepresentationPtr &  gsr 
) const
protected

Definition at line 430 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getIntraGroupProximityGradients()

bool collision_detection::CollisionEnvDistanceField::getIntraGroupProximityGradients ( GroupStateRepresentationPtr &  gsr) const
protected

Definition at line 644 of file collision_env_distance_field.cpp.

Here is the caller graph for this function:

◆ getLastDistanceFieldEntry()

DistanceFieldCacheEntryConstPtr collision_detection::CollisionEnvDistanceField::getLastDistanceFieldEntry ( ) const
inline

Definition at line 126 of file collision_env_distance_field.h.

◆ getLastGroupStateRepresentation()

collision_detection::GroupStateRepresentationConstPtr collision_detection::CollisionEnvDistanceField::getLastGroupStateRepresentation ( ) const
inline

Definition at line 208 of file collision_env_distance_field.h.

◆ getPosedLinkBodyPointDecomposition()

PosedBodyPointDecompositionPtr collision_detection::CollisionEnvDistanceField::getPosedLinkBodyPointDecomposition ( const moveit::core::LinkModel ls) const
protected

Definition at line 1090 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPosedLinkBodySphereDecomposition()

PosedBodySphereDecompositionPtr collision_detection::CollisionEnvDistanceField::getPosedLinkBodySphereDecomposition ( const moveit::core::LinkModel ls,
unsigned int  ind 
) const
protected

Definition at line 1081 of file collision_env_distance_field.cpp.

Here is the caller graph for this function:

◆ getSelfCollisions()

bool collision_detection::CollisionEnvDistanceField::getSelfCollisions ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
GroupStateRepresentationPtr &  gsr 
) const
protected

Definition at line 274 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getSelfProximityGradients()

bool collision_detection::CollisionEnvDistanceField::getSelfProximityGradients ( GroupStateRepresentationPtr &  gsr) const
protected

Definition at line 355 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize()

void collision_detection::CollisionEnvDistanceField::initialize ( const std::map< std::string, std::vector< CollisionSphere >> &  link_body_decompositions,
const Eigen::Vector3d &  size,
const Eigen::Vector3d &  origin,
bool  use_signed_distance_field,
double  resolution,
double  collision_tolerance,
double  max_propogation_distance 
)

Definition at line 126 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ MOVEIT_STRUCT_FORWARD()

collision_detection::CollisionEnvDistanceField::MOVEIT_STRUCT_FORWARD ( DistanceFieldCacheEntryWorld  )

◆ notifyObjectChange()

void collision_detection::CollisionEnvDistanceField::notifyObjectChange ( const ObjectConstPtr obj,
World::Action  action 
)
protected

Definition at line 1704 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setWorld()

void collision_detection::CollisionEnvDistanceField::setWorld ( const WorldPtr &  world)
overridevirtual

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

Definition at line 1683 of file collision_env_distance_field.cpp.

Here is the call graph for this function:

◆ updateDistanceObject()

void collision_detection::CollisionEnvDistanceField::updateDistanceObject ( const std::string &  id,
CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr &  dfce,
EigenSTL::vector_Vector3d &  add_points,
EigenSTL::vector_Vector3d &  subtract_points 
)
protected

Definition at line 1730 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updatedPaddingOrScaling()

void collision_detection::CollisionEnvDistanceField::updatedPaddingOrScaling ( const std::vector< std::string > &  links)
inlineoverrideprotectedvirtual

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

Definition at line 270 of file collision_env_distance_field.h.

◆ updateGroupStateRepresentationState()

void collision_detection::CollisionEnvDistanceField::updateGroupStateRepresentationState ( const moveit::core::RobotState state,
GroupStateRepresentationPtr &  gsr 
) const
protected

Definition at line 1103 of file collision_env_distance_field.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ collision_tolerance_

double collision_detection::CollisionEnvDistanceField::collision_tolerance_
protected

Definition at line 293 of file collision_env_distance_field.h.

◆ distance_field_cache_entry_

DistanceFieldCacheEntryPtr collision_detection::CollisionEnvDistanceField::distance_field_cache_entry_
protected

Definition at line 300 of file collision_env_distance_field.h.

◆ distance_field_cache_entry_world_

DistanceFieldCacheEntryWorldPtr collision_detection::CollisionEnvDistanceField::distance_field_cache_entry_world_
protected

Definition at line 307 of file collision_env_distance_field.h.

◆ in_group_update_map_

std::map<std::string, std::map<std::string, bool> > collision_detection::CollisionEnvDistanceField::in_group_update_map_
protected

Definition at line 301 of file collision_env_distance_field.h.

◆ last_gsr_

GroupStateRepresentationPtr collision_detection::CollisionEnvDistanceField::last_gsr_
protected

Definition at line 308 of file collision_env_distance_field.h.

◆ link_body_decomposition_index_map_

std::map<std::string, unsigned int> collision_detection::CollisionEnvDistanceField::link_body_decomposition_index_map_
protected

Definition at line 297 of file collision_env_distance_field.h.

◆ link_body_decomposition_vector_

std::vector<BodyDecompositionConstPtr> collision_detection::CollisionEnvDistanceField::link_body_decomposition_vector_
protected

Definition at line 296 of file collision_env_distance_field.h.

◆ LOGGER

const rclcpp::Logger collision_detection::CollisionEnvDistanceField::LOGGER
staticprotected
Initial value:
=
rclcpp::get_logger("moveit_collision_distance_field.collision_robot_distance_field")

Definition at line 287 of file collision_env_distance_field.h.

◆ max_propogation_distance_

double collision_detection::CollisionEnvDistanceField::max_propogation_distance_
protected

Definition at line 294 of file collision_env_distance_field.h.

◆ observer_handle_

World::ObserverHandle collision_detection::CollisionEnvDistanceField::observer_handle_
protected

Definition at line 309 of file collision_env_distance_field.h.

◆ origin_

Eigen::Vector3d collision_detection::CollisionEnvDistanceField::origin_
protected

Definition at line 290 of file collision_env_distance_field.h.

◆ planning_scene_

planning_scene::PlanningScenePtr collision_detection::CollisionEnvDistanceField::planning_scene_
protected

Definition at line 304 of file collision_env_distance_field.h.

◆ pregenerated_group_state_representation_map_

std::map<std::string, GroupStateRepresentationPtr> collision_detection::CollisionEnvDistanceField::pregenerated_group_state_representation_map_
protected

Definition at line 302 of file collision_env_distance_field.h.

◆ resolution_

double collision_detection::CollisionEnvDistanceField::resolution_
protected

Definition at line 292 of file collision_env_distance_field.h.

◆ size_

Eigen::Vector3d collision_detection::CollisionEnvDistanceField::size_
protected

Definition at line 289 of file collision_env_distance_field.h.

◆ update_cache_lock_

std::mutex collision_detection::CollisionEnvDistanceField::update_cache_lock_
mutableprotected

Definition at line 299 of file collision_env_distance_field.h.

◆ update_cache_lock_world_

std::mutex collision_detection::CollisionEnvDistanceField::update_cache_lock_world_
mutableprotected

Definition at line 306 of file collision_env_distance_field.h.

◆ use_signed_distance_field_

bool collision_detection::CollisionEnvDistanceField::use_signed_distance_field_
protected

Definition at line 291 of file collision_env_distance_field.h.


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