Public Member Functions | Public Attributes | List of all members
tesseract_collision::ContactManagerConfig Struct Reference

Contains parameters used to configure a contact manager before a series of contact checks. More...

#include <types.h>

Public Member Functions

 ContactManagerConfig ()=default
 
 ContactManagerConfig (double default_margin)
 
void incrementMargins (double increment)
 Increment all margins by input amount. Useful for inflating or reducing margins. More...
 
bool operator!= (const ContactManagerConfig &rhs) const
 
bool operator== (const ContactManagerConfig &rhs) const
 
void scaleMargins (double scale)
 Scale all margins by input value. More...
 
void validate () const
 Check for errors and throw exception if they exist. More...
 

Public Attributes

tesseract_common::AllowedCollisionMatrix acm
 Additional AllowedCollisionMatrix to consider for this collision check.
More...
 
ACMOverrideType acm_override_type { ACMOverrideType::NONE }
 Specifies how to combine the ContactAllowedValidator from acm with the one preset in the contact manager. More...
 
std::optional< double > default_margin
 override the default contact margin More...
 
std::unordered_map< std::string, bool > modify_object_enabled
 Each key is an object name. Objects will be enabled/disabled based on the value. Objects that aren't in the map are unmodified from the defaults. More...
 
CollisionMarginPairData pair_margin_data
 Stores collision margin pair data. More...
 
CollisionMarginPairOverrideType pair_margin_override_type { CollisionMarginPairOverrideType::NONE }
 Identify how the collision margin pair data should be applied to the contact manager. More...
 

Detailed Description

Contains parameters used to configure a contact manager before a series of contact checks.

It should not contain information that is usually specific to a single contactTest such as CollisionObjectTransforms or specific to the way contactTests are carried out such as LVS parameters

Note
Active links were not added to this config since this config could be shared by multiple manipulators, and those are set based on which one is being checked

Definition at line 420 of file types.h.

Constructor & Destructor Documentation

◆ ContactManagerConfig() [1/2]

tesseract_collision::ContactManagerConfig::ContactManagerConfig ( )
default

◆ ContactManagerConfig() [2/2]

tesseract_collision::ContactManagerConfig::ContactManagerConfig ( double  default_margin)

Definition at line 375 of file types.cpp.

Member Function Documentation

◆ incrementMargins()

void tesseract_collision::ContactManagerConfig::incrementMargins ( double  increment)

Increment all margins by input amount. Useful for inflating or reducing margins.

Parameters
incrementAmount to increment margins

Definition at line 377 of file types.cpp.

◆ operator!=()

bool tesseract_collision::ContactManagerConfig::operator!= ( const ContactManagerConfig rhs) const

Definition at line 417 of file types.cpp.

◆ operator==()

bool tesseract_collision::ContactManagerConfig::operator== ( const ContactManagerConfig rhs) const

Definition at line 406 of file types.cpp.

◆ scaleMargins()

void tesseract_collision::ContactManagerConfig::scaleMargins ( double  scale)

Scale all margins by input value.

Parameters
scaleValue by which all margins are multiplied

Definition at line 386 of file types.cpp.

◆ validate()

void tesseract_collision::ContactManagerConfig::validate ( ) const

Check for errors and throw exception if they exist.

Exceptions
anexception if margin_data_override_type is set to NONE, but margin pair data exist; or if acm_override_type is set to NONE but allowed collision entries exist.

Definition at line 395 of file types.cpp.

Member Data Documentation

◆ acm

tesseract_common::AllowedCollisionMatrix tesseract_collision::ContactManagerConfig::acm

Additional AllowedCollisionMatrix to consider for this collision check.

Definition at line 434 of file types.h.

◆ acm_override_type

ACMOverrideType tesseract_collision::ContactManagerConfig::acm_override_type { ACMOverrideType::NONE }

Specifies how to combine the ContactAllowedValidator from acm with the one preset in the contact manager.

Definition at line 436 of file types.h.

◆ default_margin

std::optional<double> tesseract_collision::ContactManagerConfig::default_margin

override the default contact margin

Definition at line 426 of file types.h.

◆ modify_object_enabled

std::unordered_map<std::string, bool> tesseract_collision::ContactManagerConfig::modify_object_enabled

Each key is an object name. Objects will be enabled/disabled based on the value. Objects that aren't in the map are unmodified from the defaults.

Definition at line 440 of file types.h.

◆ pair_margin_data

CollisionMarginPairData tesseract_collision::ContactManagerConfig::pair_margin_data

Stores collision margin pair data.

Definition at line 431 of file types.h.

◆ pair_margin_override_type

CollisionMarginPairOverrideType tesseract_collision::ContactManagerConfig::pair_margin_override_type { CollisionMarginPairOverrideType::NONE }

Identify how the collision margin pair data should be applied to the contact manager.

Definition at line 429 of file types.h.


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


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:53