Public Member Functions | Private Member Functions | Private Attributes | List of all members
collision_detection::AllowedCollisionMatrix Class Reference

Definition of a structure for the allowed collision matrix. More...

#include <collision_matrix.h>

Public Member Functions

 AllowedCollisionMatrix ()
 
 AllowedCollisionMatrix (const moveit_msgs::AllowedCollisionMatrix &msg)
 Construct the structure from a message representation. More...
 
 AllowedCollisionMatrix (const srdf::Model &srdf)
 Construct from an SRDF representation. More...
 
 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...
 
void clear ()
 Clear the allowed collision matrix. More...
 
void getAllEntryNames (std::vector< std::string > &names) const
 Get all the names known to the collision matrix. 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...
 
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 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 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...
 
void getMessage (moveit_msgs::AllowedCollisionMatrix &msg) const
 Get the allowed collision matrix as a message. More...
 
std::size_t getSize () const
 Get the size of the allowed collision matrix (number of specified entries) 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 print (std::ostream &out) const
 Print the allowed collision matrix. More...
 
void removeEntry (const std::string &name)
 Remove all entries corresponding to a name (all pairs that include this name) 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 setDefaultEntry (const std::string &name, bool allowed)
 Set the default value for entries that include name but are not set explicity with setEntry(). More...
 
void setDefaultEntry (const std::string &name, const DecideContactFn &fn)
 Set the default value for entries that include name but are not set explicity with setEntry(). More...
 
void setEntry (bool allowed)
 Set an entry corresponding to all known pairs. 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::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, const DecideContactFn &fn)
 Set an entry corresponding to a pair of elements. 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...
 

Private Member Functions

bool getDefaultEntry (const std::string &name1, const std::string &name2, AllowedCollision::Type &allowed_collision) const
 

Private Attributes

std::map< std::string, std::map< std::string, DecideContactFn > > allowed_contacts_
 
std::map< std::string, DecideContactFndefault_allowed_contacts_
 
std::map< std::string, AllowedCollision::Typedefault_entries_
 
std::map< std::string, std::map< std::string, AllowedCollision::Type > > entries_
 

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 112 of file collision_matrix.h.

Constructor & Destructor Documentation

◆ AllowedCollisionMatrix() [1/4]

collision_detection::AllowedCollisionMatrix::AllowedCollisionMatrix ( )

Definition at line 75 of file collision_matrix.cpp.

◆ AllowedCollisionMatrix() [2/4]

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 79 of file collision_matrix.cpp.

◆ AllowedCollisionMatrix() [3/4]

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

Construct from an SRDF representation.

Definition at line 86 of file collision_matrix.cpp.

◆ AllowedCollisionMatrix() [4/4]

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

Construct the structure from a message representation.

Definition at line 99 of file collision_matrix.cpp.

Member Function Documentation

◆ clear()

void collision_detection::AllowedCollisionMatrix::clear ( )

Clear the allowed collision matrix.

Definition at line 363 of file collision_matrix.cpp.

◆ getAllEntryNames()

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

Get all the names known to the collision matrix.

Definition at line 371 of file collision_matrix.cpp.

◆ 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 357 of file collision_matrix.cpp.

◆ 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 312 of file collision_matrix.cpp.

◆ getDefaultEntry() [1/3]

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 289 of file collision_matrix.cpp.

◆ getDefaultEntry() [2/3]

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 298 of file collision_matrix.cpp.

◆ getDefaultEntry() [3/3]

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

Definition at line 333 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 145 of file collision_matrix.cpp.

◆ 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 133 of file collision_matrix.cpp.

◆ getMessage()

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

Get the allowed collision matrix as a message.

Definition at line 385 of file collision_matrix.cpp.

◆ 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 226 of file collision_matrix.h.

◆ 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 158 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 163 of file collision_matrix.cpp.

◆ print()

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

Print the allowed collision matrix.

Definition at line 419 of file collision_matrix.cpp.

◆ 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 200 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 210 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 explicity 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 276 of file collision_matrix.cpp.

◆ setDefaultEntry() [2/2]

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

Set the default value for entries that include name but are not set explicity 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 283 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 268 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 257 of file collision_matrix.cpp.

◆ 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 243 of file collision_matrix.cpp.

◆ 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 172 of file collision_matrix.cpp.

◆ setEntry() [5/6]

void collision_detection::AllowedCollisionMatrix::setEntry ( const std::string &  name1,
const std::string &  name2,
const 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 194 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 250 of file collision_matrix.cpp.

Member Data Documentation

◆ allowed_contacts_

std::map<std::string, std::map<std::string, DecideContactFn> > collision_detection::AllowedCollisionMatrix::allowed_contacts_
private

Definition at line 281 of file collision_matrix.h.

◆ default_allowed_contacts_

std::map<std::string, DecideContactFn> collision_detection::AllowedCollisionMatrix::default_allowed_contacts_
private

Definition at line 284 of file collision_matrix.h.

◆ default_entries_

std::map<std::string, AllowedCollision::Type> collision_detection::AllowedCollisionMatrix::default_entries_
private

Definition at line 283 of file collision_matrix.h.

◆ entries_

std::map<std::string, std::map<std::string, AllowedCollision::Type> > collision_detection::AllowedCollisionMatrix::entries_
private

Definition at line 280 of file collision_matrix.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:41