Gazebo Sim

API Reference

8.7.0
CanonicalLinkModelTracker Class Reference

Helper class that keeps track of which models have a particular canonical link. This is useful in the physics system for updating model poses - if a canonical link moved in the most recent physics step, then all of the models that have this canonical link should be updated. It's important to preserve topological ordering of the models in case there's a nested model that shares the same canonical link (in a case like this, the parent model pose needs to be updated before updating the child model pose - see the documentation that explains how model pose updates are calculated in PhysicsPrivate::UpdateSim to understand why nested model poses need to be updated in topological order). More...

#include <CanonicalLinkModelTracker.hh>

Public Member Functions

void AddAllModels (const EntityComponentManager &_ecm)
 Save mappings for all models and their canonical links. More...
 
void AddNewModels (const EntityComponentManager &_ecm)
 Save mappings for new models and their canonical links. More...
 
const std::set< Entity > & CanonicalLinkModels (const Entity _canonicalLink) const
 Get a topological ordering of models that have a particular canonical link. More...
 
void RemoveLink (const Entity &_link)
 Remove a link from the mapping. This method should be called when a link is removed from simulation. More...
 

Detailed Description

Helper class that keeps track of which models have a particular canonical link. This is useful in the physics system for updating model poses - if a canonical link moved in the most recent physics step, then all of the models that have this canonical link should be updated. It's important to preserve topological ordering of the models in case there's a nested model that shares the same canonical link (in a case like this, the parent model pose needs to be updated before updating the child model pose - see the documentation that explains how model pose updates are calculated in PhysicsPrivate::UpdateSim to understand why nested model poses need to be updated in topological order).

It's possible to loop through all of the models and to update poses if the model moved using something like EntityComponentManager::Each, but the performance of this approach is worse than using just the moved canonical links to determine which model poses should be updated (consider the case where there are a lot of non-static models in a world, but only a few move frequently - if using EntityComponentManager::Each, we still need to check every single non-static model after a physics update to make sure that the model did not move. If we instead use the updated canonical link information, then we can skip iterating over/checking the models that don't need to be updated).

Member Function Documentation

◆ AddAllModels()

void AddAllModels ( const EntityComponentManager _ecm)

Save mappings for all models and their canonical links.

Parameters
[in]_ecmEntityComponentManager

References EntityComponentManager::Each(), and unordered_map< K, T >::insert().

◆ AddNewModels()

void AddNewModels ( const EntityComponentManager _ecm)

Save mappings for new models and their canonical links.

Parameters
[in]_ecmEntityComponentManager

References EntityComponentManager::EachNew(), and unordered_map< K, T >::insert().

◆ CanonicalLinkModels()

const std::set< Entity > & CanonicalLinkModels ( const Entity  _canonicalLink) const

Get a topological ordering of models that have a particular canonical link.

Parameters
[in]_canonicalLinkThe canonical link
Returns
The models that have this link as their canonical link, in topological order

References unordered_map< K, T >::end(), and unordered_map< K, T >::find().

◆ RemoveLink()

void RemoveLink ( const Entity _link)

Remove a link from the mapping. This method should be called when a link is removed from simulation.

Parameters
[in]_linkThe link to remove

References unordered_map< K, T >::erase().


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