Public Member Functions | Private Attributes
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>

List of all members.

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).
 AllowedCollisionMatrix (const moveit_msgs::AllowedCollisionMatrix &msg)
 Construct the structure from a message representation.
 AllowedCollisionMatrix (const AllowedCollisionMatrix &acm)
 Copy constructor.
void clear ()
 Clear the allowed collision matrix.
void getAllEntryNames (std::vector< std::string > &names) const
 Get all the names known to the collision matrix.
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. Default values take precedence. If a default value is specified for either name1 or name2, that value is returned instead (if both elements have default values specified, both predicates must be satisfied). If no default values are specified, getEntry() is used to look for the pair (name1, name2).
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. Default values take precedence. If a default value is specified for either name1 or name2, that value is returned instead (if both elements have default values specified, AllowedCollision::NEVER takes precedence). If no default values are specified, getEntry() is used to look for the pair (name1, name2).
bool getDefaultEntry (const std::string &name, AllowedCollision::Type &allowed_collision) 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.
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.
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.
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 entry is included in the collision matrix (if the type is AllowedCollision::CONDITIONAL). Return false if the entry is not found.
void getMessage (moveit_msgs::AllowedCollisionMatrix &msg) const
 Get the allowed collision matrix as a message.
std::size_t getSize () const
 Get the size of the allowed collision matrix (number of specified entries)
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.
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.
void print (std::ostream &out) const
 Print the allowed collision matrix.
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.
void removeEntry (const std::string &name)
 Remove all entries corresponding to a name (all pairs that include this name)
void setDefaultEntry (const std::string &name, bool allowed)
 Set the default value for entries that include name. If such a default value is set, queries to getAllowedCollision() that include name will return this value instead, even if a pair that includes name was previously specified with setEntry().
void setDefaultEntry (const std::string &name, const DecideContactFn &fn)
 Set the default value for entries that include name to be AllowedCollision::CONDITIONAL and specify the allowed contact predicate to be fn. If this function is called, queries to getAllowedCollision() that include name will return this value instead, even if a pair that includes name was previously specified with setEntry().
void setEntry (const std::string &name1, const std::string &name2, bool allowed)
 Set an entry corresponding to a pair of elements.
void 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.
void setEntry (const std::string &name, bool allowed)
 Set the entries corresponding to a name. With each of the 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.
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.
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.
void setEntry (bool allowed)
 Set an entry corresponding to all known pairs.

Private Attributes

std::map< std::string,
std::map< std::string,
DecideContactFn > > 
allowed_contacts_
std::map< std::string,
DecideContactFn
default_allowed_contacts_
std::map< std::string,
AllowedCollision::Type
default_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 81 of file collision_matrix.h.


Constructor & Destructor Documentation

Definition at line 41 of file collision_matrix.cpp.

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

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

Construct the structure from a message representation.

Definition at line 52 of file collision_matrix.cpp.

Copy constructor.

Definition at line 72 of file collision_matrix.cpp.


Member Function Documentation

Clear the allowed collision matrix.

Definition at line 330 of file collision_matrix.cpp.

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

Get all the names known to the collision matrix.

Definition at line 338 of file collision_matrix.cpp.

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. Default values take precedence. If a default value is specified for either name1 or name2, that value is returned instead (if both elements have default values specified, both predicates must be satisfied). If no default values are specified, getEntry() is used to look for the pair (name1, name2).

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

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. Default values take precedence. If a default value is specified for either name1 or name2, that value is returned instead (if both elements have default values specified, AllowedCollision::NEVER takes precedence). If no default values are specified, getEntry() is used to look for the pair (name1, name2).

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

Definition at line 299 of file collision_matrix.cpp.

bool collision_detection::AllowedCollisionMatrix::getDefaultEntry ( const std::string &  name,
AllowedCollision::Type allowed_collision 
) 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
allowed_collisionThe default allowed collision type will be filled here

Definition at line 247 of file collision_matrix.cpp.

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
fnA callback function that is used to decide if collisions are allowed between the two elements is filled here.

Definition at line 257 of file collision_matrix.cpp.

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

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 entry is included in the collision matrix (if the type is AllowedCollision::CONDITIONAL). 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 80 of file collision_matrix.cpp.

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

Get the allowed collision matrix as a message.

Definition at line 349 of file collision_matrix.cpp.

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

Definition at line 200 of file collision_matrix.h.

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

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

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

Print the allowed collision matrix.

Definition at line 385 of file collision_matrix.cpp.

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

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

Parameters:
namenamespace

Definition at line 152 of file collision_matrix.cpp.

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

Set the default value for entries that include name. If such a default value is set, queries to getAllowedCollision() that include name will return this value instead, even if a pair that includes name was previously specified 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 234 of file collision_matrix.cpp.

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

Set the default value for entries that include name to be AllowedCollision::CONDITIONAL and specify the allowed contact predicate to be fn. If this function is called, queries to getAllowedCollision() that include name will return this value instead, even if a pair that includes name was previously specified 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 241 of file collision_matrix.cpp.

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

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 is expected here

Definition at line 145 of file collision_matrix.cpp.

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

Set the entries corresponding to a name. With each of the 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.

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

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

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

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


Member Data Documentation

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

Definition at line 275 of file collision_matrix.h.

Definition at line 278 of file collision_matrix.h.

Definition at line 277 of file collision_matrix.h.

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

Definition at line 274 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 Mon Jul 24 2017 02:20:44