moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
collision_detection::AllowedCollisionMatrix Class Reference

Definition of a structure for the allowed collision matrix. All elements in the collision world are referred to by their names. This class represents which collisions are allowed to happen and which are not. More...

#include <collision_matrix.h>

Public Member Functions

 AllowedCollisionMatrix ()
 
 AllowedCollisionMatrix (const std::vector< std::string > &names, bool allowed=false)
 Instantiate using a vector of names (corresponding to all the elements in the collision world). More...
 
 AllowedCollisionMatrix (const srdf::Model &srdf)
 Construct from an SRDF representation. More...
 
 AllowedCollisionMatrix (const moveit_msgs::msg::AllowedCollisionMatrix &msg)
 Construct the structure from a message representation. More...
 
 AllowedCollisionMatrix (const AllowedCollisionMatrix &acm)=default
 Copy constructor. More...
 
AllowedCollisionMatrixoperator= (const AllowedCollisionMatrix &)=default
 Copy assignment. More...
 
bool getEntry (const std::string &name1, const std::string &name2, AllowedCollision::Type &allowed_collision_type) const
 Get the type of the allowed collision between two elements. Return true if the entry is included in the collision matrix. Return false if the entry is not found. More...
 
bool getEntry (const std::string &name1, const std::string &name2, DecideContactFn &fn) const
 Get the allowed collision predicate between two elements. Return true if a predicate for this entry is available in the collision matrix. Return false if the entry is not found. More...
 
bool hasEntry (const std::string &name) const
 Check if the allowed collision matrix has an entry at all for an element. Returns true if the element is included. More...
 
bool hasEntry (const std::string &name1, const std::string &name2) const
 Check if the allowed collision matrix has an entry for a pair of elements. Returns true if the pair is included. More...
 
void removeEntry (const std::string &name1, const std::string &name2)
 Remove an entry corresponding to a pair of elements. Nothing happens if the pair does not exist in the collision matrix. More...
 
void removeEntry (const std::string &name)
 Remove all entries corresponding to a name (all pairs that include this name) More...
 
void setEntry (const std::string &name1, const std::string &name2, bool allowed)
 Set an entry corresponding to a pair of elements. More...
 
void setEntry (const std::string &name1, const std::string &name2, DecideContactFn &fn)
 Set an entry corresponding to a pair of elements. More...
 
void setEntry (const std::string &name, bool allowed)
 Set the entries corresponding to a name. With each of the known names in the collision matrix, form a pair using the name specified as argument to this function and set the entry as indicated by allowed. As the set of known names might change in future, consider using setDefaultEntry() instead! More...
 
void setEntry (const std::string &name, const std::vector< std::string > &other_names, bool allowed)
 Set multiple entries. Pairs of names are formed using name and other_names. More...
 
void setEntry (const std::vector< std::string > &names1, const std::vector< std::string > &names2, bool allowed)
 Set an entry corresponding to all possible pairs between two sets of elements. More...
 
void setEntry (bool allowed)
 Set an entry corresponding to all known pairs. More...
 
void getAllEntryNames (std::vector< std::string > &names) const
 Get all the names known to the collision matrix. More...
 
void getMessage (moveit_msgs::msg::AllowedCollisionMatrix &msg) const
 Get the allowed collision matrix as a message. More...
 
void clear ()
 Clear the allowed collision matrix. More...
 
std::size_t getSize () const
 Get the size of the allowed collision matrix (number of specified entries) More...
 
void setDefaultEntry (const std::string &name, bool allowed)
 Set the default value for entries that include name but are not set explicitly with setEntry(). More...
 
void setDefaultEntry (const std::string &name, DecideContactFn &fn)
 Set the default value for entries that include name but are not set explicitly with setEntry(). More...
 
bool getDefaultEntry (const std::string &name, AllowedCollision::Type &allowed_collision) const
 Get the type of the allowed collision to be considered by default for an element. Return true if a default value was found for the specified element. Return false otherwise. More...
 
bool getDefaultEntry (const std::string &name, DecideContactFn &fn) const
 Get the type of the allowed collision between to be considered by default for an element. Return true if a default value was found for the specified element. Return false otherwise. More...
 
bool getAllowedCollision (const std::string &name1, const std::string &name2, DecideContactFn &fn) const
 Get the allowed collision predicate between two elements. Return true if a predicate for entry is included in the collision matrix (if the type is AllowedCollision::CONDITIONAL) or if one was computed from defaults. Return false if the entry is not found. More...
 
bool getAllowedCollision (const std::string &name1, const std::string &name2, AllowedCollision::Type &allowed_collision) const
 Get the type of the allowed collision between two elements. Return true if the entry is included in the collision matrix or if specified defaults were found. Return false if the entry is not found. More...
 
void print (std::ostream &out) const
 Print the allowed collision matrix. More...
 

Detailed Description

Definition of a structure for the allowed collision matrix. All elements in the collision world are referred to by their names. This class represents which collisions are allowed to happen and which are not.

Definition at line 79 of file collision_matrix.h.

Constructor & Destructor Documentation

◆ AllowedCollisionMatrix() [1/5]

collision_detection::AllowedCollisionMatrix::AllowedCollisionMatrix ( )

Definition at line 48 of file collision_matrix.cpp.

◆ AllowedCollisionMatrix() [2/5]

collision_detection::AllowedCollisionMatrix::AllowedCollisionMatrix ( const std::vector< std::string > &  names,
bool  allowed = false 
)

Instantiate using a vector of names (corresponding to all the elements in the collision world).

Parameters
namesa vector of names (corresponding to object IDs in the collision world).
allowedIf false, indicates that collisions between all elements must be checked for and no collisions will be ignored.

Definition at line 52 of file collision_matrix.cpp.

Here is the call graph for this function:

◆ AllowedCollisionMatrix() [3/5]

collision_detection::AllowedCollisionMatrix::AllowedCollisionMatrix ( const srdf::Model &  srdf)

Construct from an SRDF representation.

Definition at line 59 of file collision_matrix.cpp.

Here is the call graph for this function:

◆ AllowedCollisionMatrix() [4/5]

collision_detection::AllowedCollisionMatrix::AllowedCollisionMatrix ( const moveit_msgs::msg::AllowedCollisionMatrix &  msg)

Construct the structure from a message representation.

Definition at line 72 of file collision_matrix.cpp.

Here is the call graph for this function:

◆ AllowedCollisionMatrix() [5/5]

collision_detection::AllowedCollisionMatrix::AllowedCollisionMatrix ( const AllowedCollisionMatrix acm)
default

Copy constructor.

Member Function Documentation

◆ clear()

void collision_detection::AllowedCollisionMatrix::clear ( )

Clear the allowed collision matrix.

Definition at line 337 of file collision_matrix.cpp.

Here is the caller graph for this function:

◆ getAllEntryNames()

void collision_detection::AllowedCollisionMatrix::getAllEntryNames ( std::vector< std::string > &  names) const

Get all the names known to the collision matrix.

Definition at line 345 of file collision_matrix.cpp.

Here is the caller graph for this function:

◆ getAllowedCollision() [1/2]

bool collision_detection::AllowedCollisionMatrix::getAllowedCollision ( const std::string &  name1,
const std::string &  name2,
AllowedCollision::Type allowed_collision 
) const

Get the type of the allowed collision between two elements. Return true if the entry is included in the collision matrix or if specified defaults were found. Return false if the entry is not found.

Parameters
name1name of first element
name2name of second element
allowed_collisionThe allowed collision type will be filled here

Definition at line 331 of file collision_matrix.cpp.

Here is the call graph for this function:

◆ getAllowedCollision() [2/2]

bool collision_detection::AllowedCollisionMatrix::getAllowedCollision ( const std::string &  name1,
const std::string &  name2,
DecideContactFn fn 
) const

Get the allowed collision predicate between two elements. Return true if a predicate for entry is included in the collision matrix (if the type is AllowedCollision::CONDITIONAL) or if one was computed from defaults. Return false if the entry is not found.

Parameters
name1name of first element
name2name of second element
fnReturn the callback function that is used to decide if collisions are allowed between the two elements.

Definition at line 286 of file collision_matrix.cpp.

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

◆ getDefaultEntry() [1/2]

bool collision_detection::AllowedCollisionMatrix::getDefaultEntry ( const std::string &  name,
AllowedCollision::Type allowed_collision 
) const

Get the type of the allowed collision to be considered by default for an element. Return true if a default value was found for the specified element. Return false otherwise.

Parameters
namename of the element
allowed_collisionThe default allowed collision type will be filled here

Definition at line 263 of file collision_matrix.cpp.

Here is the caller graph for this function:

◆ getDefaultEntry() [2/2]

bool collision_detection::AllowedCollisionMatrix::getDefaultEntry ( const std::string &  name,
DecideContactFn fn 
) const

Get the type of the allowed collision between to be considered by default for an element. Return true if a default value was found for the specified element. Return false otherwise.

Parameters
namename of the element
fnReturn the callback function that is used to decide if collisions are allowed between the two elements.

Definition at line 272 of file collision_matrix.cpp.

◆ getEntry() [1/2]

bool collision_detection::AllowedCollisionMatrix::getEntry ( const std::string &  name1,
const std::string &  name2,
AllowedCollision::Type allowed_collision_type 
) const

Get the type of the allowed collision between two elements. Return true if the entry is included in the collision matrix. Return false if the entry is not found.

Parameters
name1name of first element
name2name of second element
allowed_collision_typeThe allowed collision type will be filled here

Definition at line 118 of file collision_matrix.cpp.

Here is the caller graph for this function:

◆ getEntry() [2/2]

bool collision_detection::AllowedCollisionMatrix::getEntry ( const std::string &  name1,
const std::string &  name2,
DecideContactFn fn 
) const

Get the allowed collision predicate between two elements. Return true if a predicate for this entry is available in the collision matrix. Return false if the entry is not found.

Parameters
name1name of first element
name2name of second element
fnA callback function that is used to decide if collisions are allowed between the two elements is filled here

Definition at line 106 of file collision_matrix.cpp.

◆ getMessage()

void collision_detection::AllowedCollisionMatrix::getMessage ( moveit_msgs::msg::AllowedCollisionMatrix &  msg) const

Get the allowed collision matrix as a message.

Definition at line 359 of file collision_matrix.cpp.

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

◆ getSize()

std::size_t collision_detection::AllowedCollisionMatrix::getSize ( ) const
inline

Get the size of the allowed collision matrix (number of specified entries)

Definition at line 199 of file collision_matrix.h.

Here is the caller graph for this function:

◆ hasEntry() [1/2]

bool collision_detection::AllowedCollisionMatrix::hasEntry ( const std::string &  name) const

Check if the allowed collision matrix has an entry at all for an element. Returns true if the element is included.

Parameters
namename of the element

Definition at line 131 of file collision_matrix.cpp.

◆ hasEntry() [2/2]

bool collision_detection::AllowedCollisionMatrix::hasEntry ( const std::string &  name1,
const std::string &  name2 
) const

Check if the allowed collision matrix has an entry for a pair of elements. Returns true if the pair is included.

Parameters
name1name of first element
name2name of second element

Definition at line 136 of file collision_matrix.cpp.

◆ operator=()

AllowedCollisionMatrix& collision_detection::AllowedCollisionMatrix::operator= ( const AllowedCollisionMatrix )
default

Copy assignment.

◆ print()

void collision_detection::AllowedCollisionMatrix::print ( std::ostream &  out) const

Print the allowed collision matrix.

Definition at line 393 of file collision_matrix.cpp.

Here is the call graph for this function:

◆ removeEntry() [1/2]

void collision_detection::AllowedCollisionMatrix::removeEntry ( const std::string &  name)

Remove all entries corresponding to a name (all pairs that include this name)

Parameters
namenamespace

Definition at line 173 of file collision_matrix.cpp.

◆ removeEntry() [2/2]

void collision_detection::AllowedCollisionMatrix::removeEntry ( const std::string &  name1,
const std::string &  name2 
)

Remove an entry corresponding to a pair of elements. Nothing happens if the pair does not exist in the collision matrix.

Parameters
name1name of first element
name2name of second element

Definition at line 183 of file collision_matrix.cpp.

◆ setDefaultEntry() [1/2]

void collision_detection::AllowedCollisionMatrix::setDefaultEntry ( const std::string &  name,
bool  allowed 
)

Set the default value for entries that include name but are not set explicitly with setEntry().

Parameters
nameThe name of the element for which to set the default value
allowedIf false, indicates that collisions between name and any other element must be checked for and no collisions will be ignored (AllowedCollision::NEVER). If true, indicates that collisions between name and any other element are ok and an explicit collision computation is not necessary (AllowedCollision::ALWAYS).

Definition at line 250 of file collision_matrix.cpp.

Here is the caller graph for this function:

◆ setDefaultEntry() [2/2]

void collision_detection::AllowedCollisionMatrix::setDefaultEntry ( const std::string &  name,
DecideContactFn fn 
)

Set the default value for entries that include name but are not set explicitly with setEntry().

Parameters
nameThe name of the element for which to set the default value
fnA callback function that is used to decide if collisions are allowed between name and some other element is expected here.

Definition at line 257 of file collision_matrix.cpp.

◆ setEntry() [1/6]

void collision_detection::AllowedCollisionMatrix::setEntry ( bool  allowed)

Set an entry corresponding to all known pairs.

Parameters
allowedIf false, indicates that collisions between two elements must be checked for and no collisions will be ignored (AllowedCollision::NEVER). If true, indicates that collisions between two elements are ok and an explicit collision computation is not necessary (AllowedCollision::ALWAYS).

Definition at line 242 of file collision_matrix.cpp.

◆ setEntry() [2/6]

void collision_detection::AllowedCollisionMatrix::setEntry ( const std::string &  name,
bool  allowed 
)

Set the entries corresponding to a name. With each of the known names in the collision matrix, form a pair using the name specified as argument to this function and set the entry as indicated by allowed. As the set of known names might change in future, consider using setDefaultEntry() instead!

Parameters
namethe object name
allowedIf false, indicates that collisions between two elements must be checked for and no collisions will be ignored (AllowedCollision::NEVER). If true, indicates that collisions between two elements are ok and an explicit collision computation is not necessary (AllowedCollision::ALWAYS).

Definition at line 231 of file collision_matrix.cpp.

Here is the call graph for this function:

◆ setEntry() [3/6]

void collision_detection::AllowedCollisionMatrix::setEntry ( const std::string &  name,
const std::vector< std::string > &  other_names,
bool  allowed 
)

Set multiple entries. Pairs of names are formed using name and other_names.

Parameters
namename of first element
other_namesnames of all other elements to pair with first element. The collision matrix entries will be set for all such pairs.
allowedIf false, indicates that collisions between two elements must be checked for and no collisions will be ignored (AllowedCollision::NEVER). If true, indicates that collisions between two elements are ok and an explicit collision computation is not necessary (AllowedCollision::ALWAYS).

Definition at line 216 of file collision_matrix.cpp.

Here is the call graph for this function:

◆ setEntry() [4/6]

void collision_detection::AllowedCollisionMatrix::setEntry ( const std::string &  name1,
const std::string &  name2,
bool  allowed 
)

Set an entry corresponding to a pair of elements.

Parameters
name1name of first element
name2name of second element
allowedIf false, indicates that collisions between two elements must be checked for and no collisions will be ignored (AllowedCollision::NEVER). If true, indicates that collisions between two elements are ok and an explicit collision computation is not necessary (AllowedCollision::ALWAYS).

Definition at line 145 of file collision_matrix.cpp.

Here is the caller graph for this function:

◆ setEntry() [5/6]

void collision_detection::AllowedCollisionMatrix::setEntry ( const std::string &  name1,
const std::string &  name2,
DecideContactFn fn 
)

Set an entry corresponding to a pair of elements.

This sets the type of the entry to AllowedCollision::CONDITIONAL.

Parameters
name1name of first element
name2name of second element
fnA callback function that is used to decide if collisions are allowed between the two elements

Definition at line 167 of file collision_matrix.cpp.

◆ setEntry() [6/6]

void collision_detection::AllowedCollisionMatrix::setEntry ( const std::vector< std::string > &  names1,
const std::vector< std::string > &  names2,
bool  allowed 
)

Set an entry corresponding to all possible pairs between two sets of elements.

Parameters
names1First set of names
names2Second set of names
allowedIf false, indicates that collisions between two elements must be checked for and no collisions will be ignored (AllowedCollision::NEVER). If true, indicates that collisions between two elements are ok and an explicit collision computation is not necessary (AllowedCollision::ALWAYS).

Definition at line 224 of file collision_matrix.cpp.

Here is the call graph for this function:

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