discrete_contact_manager.cpp
Go to the documentation of this file.
1 
29 
30 namespace tesseract_collision
31 {
33 {
34  config.validate();
35 
36  if (config.default_margin.has_value())
38 
42 }
43 } // namespace tesseract_collision
tesseract_collision::ContactManagerConfig::validate
void validate() const
Check for errors and throw exception if they exist.
Definition: types.cpp:395
tesseract_collision::ContactManagerConfig
Contains parameters used to configure a contact manager before a series of contact checks.
Definition: types.h:420
tesseract_collision::DiscreteContactManager::setDefaultCollisionMargin
virtual void setDefaultCollisionMargin(double default_collision_margin)=0
Set the default collision margin.
discrete_contact_manager.h
This is the discrete contact manager base class.
tesseract_collision::ContactManagerConfig::modify_object_enabled
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 ...
Definition: types.h:440
utils.h
Tesseract Collision utils.
tesseract_collision::ContactManagerConfig::default_margin
std::optional< double > default_margin
override the default contact margin
Definition: types.h:426
tesseract_collision::DiscreteContactManager::applyContactManagerConfig
virtual void applyContactManagerConfig(const ContactManagerConfig &config)
Applies settings in the config.
Definition: discrete_contact_manager.cpp:32
tesseract_collision::DiscreteContactManager::setCollisionMarginPairData
virtual void setCollisionMarginPairData(const CollisionMarginPairData &pair_margin_data, CollisionMarginPairOverrideType override_type=CollisionMarginPairOverrideType::REPLACE)=0
Set the contact distance thresholds for which collision should be considered on a per pair basis.
tesseract_collision::ContactManagerConfig::pair_margin_override_type
CollisionMarginPairOverrideType pair_margin_override_type
Identify how the collision margin pair data should be applied to the contact manager.
Definition: types.h:429
tesseract_collision::applyContactAllowedValidatorOverride
void applyContactAllowedValidatorOverride(ManagerType &manager, const tesseract_common::AllowedCollisionMatrix &acm, ACMOverrideType type)
Applies ACM to contact manager using override type.
Definition: utils.h:53
tesseract_collision::applyModifyObjectEnabled
void applyModifyObjectEnabled(ManagerType &manager, const std::unordered_map< std::string, bool > &modify_object_enabled)
Loops over the map and for every object string either enables or disables it based on the value (true...
Definition: utils.h:69
tesseract_collision::ContactManagerConfig::pair_margin_data
CollisionMarginPairData pair_margin_data
Stores collision margin pair data.
Definition: types.h:431
tesseract_collision
Definition: bullet_cast_bvh_manager.h:48
tesseract_collision::ContactManagerConfig::acm
tesseract_common::AllowedCollisionMatrix acm
Additional AllowedCollisionMatrix to consider for this collision check.
Definition: types.h:434
tesseract_collision::ContactManagerConfig::acm_override_type
ACMOverrideType acm_override_type
Specifies how to combine the ContactAllowedValidator from acm with the one preset in the contact mana...
Definition: types.h:436


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