25
25
#include < algorithm>
26
26
#include < iostream>
27
27
#include < deque>
28
+ #include < map>
28
29
#include < string>
29
30
#include < unordered_map>
30
31
#include < unordered_set>
119
120
#include " ignition/gazebo/components/ThreadPitch.hh"
120
121
#include " ignition/gazebo/components/World.hh"
121
122
123
+ #include " CanonicalLinkModelTracker.hh"
122
124
#include " EntityFeatureMap.hh"
123
125
124
126
using namespace ignition ;
@@ -193,7 +195,10 @@ class ignition::gazebo::systems::PhysicsPrivate
193
195
// / not write this data to ForwardStep::Output. If not, _ecm is used to get
194
196
// / this updated link pose data).
195
197
// / \return A map of gazebo link entities to their updated pose data.
196
- public: std::unordered_map<Entity, physics::FrameData3d> ChangedLinks (
198
+ // / std::map is used because canonical links must be in topological order
199
+ // / to ensure that nested models with multiple canonical links are updated
200
+ // / properly (models must be updated in topological order).
201
+ public: std::map<Entity, physics::FrameData3d> ChangedLinks (
197
202
EntityComponentManager &_ecm,
198
203
const ignition::physics::ForwardStep::Output &_updatedLinks);
199
204
@@ -203,7 +208,7 @@ class ignition::gazebo::systems::PhysicsPrivate
203
208
// / most recent physics step. The key is the entity of the link, and the
204
209
// / value is the updated frame data corresponding to that entity.
205
210
public: void UpdateSim (EntityComponentManager &_ecm,
206
- const std::unordered_map <
211
+ const std::map <
207
212
Entity, physics::FrameData3d> &_linkFrameData);
208
213
209
214
// / \brief Update collision components from physics simulation
@@ -237,6 +242,11 @@ class ignition::gazebo::systems::PhysicsPrivate
237
242
// / after a physics step.
238
243
public: std::unordered_map<Entity, ignition::math::Pose3d> linkWorldPoses;
239
244
245
+ // / \brief Keep a mapping of canonical links to models that have this
246
+ // / canonical link. Useful for updating model poses efficiently after a
247
+ // / physics step
248
+ public: CanonicalLinkModelTracker canonicalLinkModelTracker;
249
+
240
250
// / \brief Keep track of non-static model world poses. Since non-static
241
251
// / models may not move on a given iteration, we want to keep track of the
242
252
// / most recent model world pose change that took place.
@@ -1178,6 +1188,7 @@ void PhysicsPrivate::RemovePhysicsEntities(const EntityComponentManager &_ecm)
1178
1188
this ->topLevelModelMap .erase (childLink);
1179
1189
this ->staticEntities .erase (childLink);
1180
1190
this ->linkWorldPoses .erase (childLink);
1191
+ this ->canonicalLinkModelTracker .RemoveLink (childLink);
1181
1192
}
1182
1193
1183
1194
for (const auto &childJoint :
@@ -1835,13 +1846,13 @@ ignition::math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from,
1835
1846
}
1836
1847
1837
1848
// ////////////////////////////////////////////////
1838
- std::unordered_map <Entity, physics::FrameData3d> PhysicsPrivate::ChangedLinks (
1849
+ std::map <Entity, physics::FrameData3d> PhysicsPrivate::ChangedLinks (
1839
1850
EntityComponentManager &_ecm,
1840
1851
const ignition::physics::ForwardStep::Output &_updatedLinks)
1841
1852
{
1842
1853
IGN_PROFILE (" Links Frame Data" );
1843
1854
1844
- std::unordered_map <Entity, physics::FrameData3d> linkFrameData;
1855
+ std::map <Entity, physics::FrameData3d> linkFrameData;
1845
1856
1846
1857
// Check to see if the physics engine gave a list of changed poses. If not, we
1847
1858
// will iterate through all of the links via the ECM to see which ones changed
@@ -1912,83 +1923,91 @@ std::unordered_map<Entity, physics::FrameData3d> PhysicsPrivate::ChangedLinks(
1912
1923
1913
1924
// ////////////////////////////////////////////////
1914
1925
void PhysicsPrivate::UpdateSim (EntityComponentManager &_ecm,
1915
- const std::unordered_map <Entity, physics::FrameData3d> &_linkFrameData)
1926
+ const std::map <Entity, physics::FrameData3d> &_linkFrameData)
1916
1927
{
1917
1928
IGN_PROFILE (" PhysicsPrivate::UpdateSim" );
1918
1929
1919
1930
IGN_PROFILE_BEGIN (" Models" );
1920
1931
1921
- _ecm.Each <components::Model, components::ModelCanonicalLink>(
1922
- [&](const Entity &_entity, components::Model *,
1923
- components::ModelCanonicalLink *_canonicalLink) -> bool
1924
- {
1925
- // If the model's canonical link did not move, we don't need to update
1926
- // the model's pose
1927
- auto linkFrameIt = _linkFrameData.find (_canonicalLink->Data ());
1928
- if (linkFrameIt == _linkFrameData.end ())
1929
- return true ;
1930
-
1931
- std::optional<math::Pose3d> parentWorldPose;
1932
+ // make sure we have an up-to-date mapping of canonical links to their models
1933
+ this ->canonicalLinkModelTracker .AddNewModels (_ecm);
1932
1934
1933
- // If this model is nested, we assume the pose of the parent model has
1934
- // already been updated. We expect to find the updated pose in
1935
- // this->modelWorldPoses. If not found, this must not be nested, so
1936
- // this model's pose component would reflect it's absolute pose.
1937
- auto parentModelPoseIt =
1938
- this ->modelWorldPoses .find (
1939
- _ecm.Component <components::ParentEntity>(_entity)->Data ());
1940
- if (parentModelPoseIt != this ->modelWorldPoses .end ())
1941
- {
1942
- parentWorldPose = parentModelPoseIt->second ;
1943
- }
1935
+ for (const auto &[linkEntity, frameData] : _linkFrameData)
1936
+ {
1937
+ // get a topological ordering of the models that have linkEntity as the
1938
+ // model's canonical link. If linkEntity isn't a canonical link for any
1939
+ // models, canonicalLinkModels will be empty
1940
+ auto canonicalLinkModels =
1941
+ this ->canonicalLinkModelTracker .CanonicalLinkModels (linkEntity);
1942
+
1943
+ // Update poses for all of the models that have this changed canonical link
1944
+ // (linkEntity). Since we have the models in topological order and
1945
+ // _linkFrameData stores links in topological order thanks to the ordering
1946
+ // of std::map (entity IDs are created in ascending order), this should
1947
+ // properly handle pose updates for nested models
1948
+ for (auto &model : canonicalLinkModels)
1949
+ {
1950
+ std::optional<math::Pose3d> parentWorldPose;
1951
+
1952
+ // If this model is nested, the pose of the parent model has already
1953
+ // been updated since we iterate through the modified links in
1954
+ // topological order. We expect to find the updated pose in
1955
+ // this->modelWorldPoses. If not found, this must not be nested, so this
1956
+ // model's pose component would reflect it's absolute pose.
1957
+ auto parentModelPoseIt =
1958
+ this ->modelWorldPoses .find (
1959
+ _ecm.Component <components::ParentEntity>(model)->Data ());
1960
+ if (parentModelPoseIt != this ->modelWorldPoses .end ())
1961
+ {
1962
+ parentWorldPose = parentModelPoseIt->second ;
1963
+ }
1944
1964
1945
- // Given the following frame names:
1946
- // W: World/inertial frame
1947
- // P: Parent frame (this could be a parent model or the World frame)
1948
- // M: This model's frame
1949
- // L: The frame of this model's canonical link
1950
- //
1951
- // And the following quantities:
1952
- // (See http://sdformat.org/tutorials?tut=specify_pose for pose
1953
- // convention)
1954
- // parentWorldPose (X_WP): Pose of the parent frame w.r.t the world
1955
- // linkPoseFromModel (X_ML): Pose of the canonical link frame w.r.t the
1956
- // model frame
1957
- // linkWorldPose (X_WL): Pose of the canonical link w.r.t the world
1958
- // modelWorldPose (X_WM): Pose of this model w.r.t the world
1959
- //
1960
- // The Pose component of this model entity stores the pose of M w.r.t P
1961
- // (X_PM) and is calculated as
1962
- // X_PM = (X_WP)^-1 * X_WM
1963
- //
1964
- // And X_WM is calculated from X_WL, which is obtained from physics as:
1965
- // X_WM = X_WL * (X_ML)^-1
1966
- auto linkPoseFromModel =
1967
- this ->RelativePose (_entity, linkFrameIt->first , _ecm);
1968
- const auto &linkWorldPose = linkFrameIt->second .pose ;
1969
- const auto &modelWorldPose =
1970
- math::eigen3::convert (linkWorldPose) * linkPoseFromModel.Inverse ();
1971
-
1972
- this ->modelWorldPoses [_entity] = modelWorldPose;
1973
-
1974
- // update model's pose
1975
- auto modelPose = _ecm.Component <components::Pose>(_entity);
1976
- if (parentWorldPose)
1977
- {
1978
- *modelPose =
1979
- components::Pose (parentWorldPose->Inverse () * modelWorldPose);
1980
- }
1981
- else
1982
- {
1983
- // This is a non-nested model and parentWorldPose would be identity
1984
- // because it would be the pose of the parent (world) w.r.t the world.
1985
- *modelPose = components::Pose (modelWorldPose);
1986
- }
1965
+ // Given the following frame names:
1966
+ // W: World/inertial frame
1967
+ // P: Parent frame (this could be a parent model or the World frame)
1968
+ // M: This model's frame
1969
+ // L: The frame of this model's canonical link
1970
+ //
1971
+ // And the following quantities:
1972
+ // (See http://sdformat.org/tutorials?tut=specify_pose for pose
1973
+ // convention)
1974
+ // parentWorldPose (X_WP): Pose of the parent frame w.r.t the world
1975
+ // linkPoseFromModel (X_ML): Pose of the canonical link frame w.r.t the
1976
+ // model frame
1977
+ // linkWorldPose (X_WL): Pose of the canonical link w.r.t the world
1978
+ // modelWorldPose (X_WM): Pose of this model w.r.t the world
1979
+ //
1980
+ // The Pose component of this model entity stores the pose of M w.r.t P
1981
+ // (X_PM) and is calculated as
1982
+ // X_PM = (X_WP)^-1 * X_WM
1983
+ //
1984
+ // And X_WM is calculated from X_WL, which is obtained from physics as:
1985
+ // X_WM = X_WL * (X_ML)^-1
1986
+ auto linkPoseFromModel = this ->RelativePose (model, linkEntity, _ecm);
1987
+ const auto &linkWorldPose = frameData.pose ;
1988
+ const auto &modelWorldPose =
1989
+ math::eigen3::convert (linkWorldPose) * linkPoseFromModel.Inverse ();
1990
+
1991
+ this ->modelWorldPoses [model] = modelWorldPose;
1992
+
1993
+ // update model's pose
1994
+ auto modelPose = _ecm.Component <components::Pose>(model);
1995
+ if (parentWorldPose)
1996
+ {
1997
+ *modelPose =
1998
+ components::Pose (parentWorldPose->Inverse () * modelWorldPose);
1999
+ }
2000
+ else
2001
+ {
2002
+ // This is a non-nested model and parentWorldPose would be identity
2003
+ // because it would be the pose of the parent (world) w.r.t the world.
2004
+ *modelPose = components::Pose (modelWorldPose);
2005
+ }
1987
2006
1988
- _ecm.SetChanged (_entity , components::Pose::typeId,
1989
- ComponentState::PeriodicChange);
1990
- return true ;
1991
- });
2007
+ _ecm.SetChanged (model , components::Pose::typeId,
2008
+ ComponentState::PeriodicChange);
2009
+ }
2010
+ }
1992
2011
IGN_PROFILE_END ();
1993
2012
1994
2013
// Link poses, velocities...
0 commit comments