Skip to content

Commit 570cb2b

Browse files
committed
Map canonical links to their models (#736)
Signed-off-by: Ashton Larkin <[email protected]>
1 parent a9cfa0d commit 570cb2b

File tree

4 files changed

+286
-77
lines changed

4 files changed

+286
-77
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,116 @@
1+
/*
2+
* Copyright (C) 2021 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
#ifndef IGNITION_GAZEBO_SYSTEMS_PHYSICS_CANONICAL_LINK_MODEL_TRACKER_HH_
18+
#define IGNITION_GAZEBO_SYSTEMS_PHYSICS_CANONICAL_LINK_MODEL_TRACKER_HH_
19+
20+
#include <set>
21+
#include <unordered_map>
22+
23+
#include "ignition/gazebo/Entity.hh"
24+
#include "ignition/gazebo/EntityComponentManager.hh"
25+
#include "ignition/gazebo/components/CanonicalLink.hh"
26+
#include "ignition/gazebo/components/Model.hh"
27+
#include "ignition/gazebo/config.hh"
28+
29+
namespace ignition::gazebo
30+
{
31+
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
32+
namespace systems::physics_system
33+
{
34+
/// \brief Helper class that keeps track of which models have a particular
35+
/// canonical link. This is useful in the physics system for updating model
36+
/// poses - if a canonical link moved in the most recent physics step, then
37+
/// all of the models that have this canonical link should be updated. It's
38+
/// important to preserve topological ordering of the models in case there's
39+
/// a nested model that shares the same canonical link (in a case like this,
40+
/// the parent model pose needs to be updated before updating the child model
41+
/// pose - see the documentation that explains how model pose updates are
42+
/// calculated in PhysicsPrivate::UpdateSim to understand why nested model
43+
/// poses need to be updated in topological order).
44+
///
45+
/// It's possible to loop through all of the models and to update poses if the
46+
/// model moved using something like EntityComponentManager::Each, but the
47+
/// performance of this approach is worse than using just the moved canonical
48+
/// links to determine which model poses should be updated (consider the case
49+
/// where there are a lot of non-static models in a world, but only a few move
50+
/// frequently - if using EntityComponentManager::Each, we still need to check
51+
/// every single non-static model after a physics update to make sure that the
52+
/// model did not move. If we instead use the updated canonical link
53+
/// information, then we can skip iterating over/checking the models that
54+
/// don't need to be updated).
55+
class CanonicalLinkModelTracker
56+
{
57+
/// \brief Save mappings for new models and their canonical links
58+
/// \param[in] _ecm EntityComponentManager
59+
public: void AddNewModels(const EntityComponentManager &_ecm);
60+
61+
/// \brief Get a topological ordering of models that have a particular
62+
/// canonical link
63+
/// \param[in] _canonicalLink The canonical link
64+
/// \return The models that have this link as their canonical link, in
65+
/// topological order
66+
public: const std::set<Entity> &CanonicalLinkModels(
67+
const Entity _canonicalLink) const;
68+
69+
/// \brief Remove a link from the mapping. This method should be called when
70+
/// a link is removed from simulation
71+
/// \param[in] _link The link to remove
72+
public: void RemoveLink(const Entity &_link);
73+
74+
/// \brief A mapping of canonical links to the models that have this
75+
/// canonical link. The key is the canonical link entity, and the value is
76+
/// the model entities that have this canonical link. The models in the
77+
/// value are in topological order
78+
private: std::unordered_map<Entity, std::set<Entity>> linkModelMap;
79+
80+
/// \brief An empty set of models that is returned from the
81+
/// CanonicalLinkModels method for links that map to no models
82+
private: const std::set<Entity> emptyModelOrdering{};
83+
};
84+
85+
void CanonicalLinkModelTracker::AddNewModels(
86+
const EntityComponentManager &_ecm)
87+
{
88+
_ecm.EachNew<components::Model, components::ModelCanonicalLink>(
89+
[this](const Entity &_model, const components::Model *,
90+
const components::ModelCanonicalLink *_canonicalLinkComp)
91+
{
92+
this->linkModelMap[_canonicalLinkComp->Data()].insert(_model);
93+
return true;
94+
});
95+
}
96+
97+
const std::set<Entity> &CanonicalLinkModelTracker::CanonicalLinkModels(
98+
const Entity _canonicalLink) const
99+
{
100+
auto it = this->linkModelMap.find(_canonicalLink);
101+
if (it != this->linkModelMap.end())
102+
return it->second;
103+
104+
// if an invalid entity was given, it maps to no models
105+
return this->emptyModelOrdering;
106+
}
107+
108+
void CanonicalLinkModelTracker::RemoveLink(const Entity &_link)
109+
{
110+
this->linkModelMap.erase(_link);
111+
}
112+
}
113+
}
114+
}
115+
116+
#endif

src/systems/physics/Physics.cc

+92-73
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <algorithm>
2626
#include <iostream>
2727
#include <deque>
28+
#include <map>
2829
#include <string>
2930
#include <unordered_map>
3031
#include <unordered_set>
@@ -119,6 +120,7 @@
119120
#include "ignition/gazebo/components/ThreadPitch.hh"
120121
#include "ignition/gazebo/components/World.hh"
121122

123+
#include "CanonicalLinkModelTracker.hh"
122124
#include "EntityFeatureMap.hh"
123125

124126
using namespace ignition;
@@ -193,7 +195,10 @@ class ignition::gazebo::systems::PhysicsPrivate
193195
/// not write this data to ForwardStep::Output. If not, _ecm is used to get
194196
/// this updated link pose data).
195197
/// \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(
197202
EntityComponentManager &_ecm,
198203
const ignition::physics::ForwardStep::Output &_updatedLinks);
199204

@@ -203,7 +208,7 @@ class ignition::gazebo::systems::PhysicsPrivate
203208
/// most recent physics step. The key is the entity of the link, and the
204209
/// value is the updated frame data corresponding to that entity.
205210
public: void UpdateSim(EntityComponentManager &_ecm,
206-
const std::unordered_map<
211+
const std::map<
207212
Entity, physics::FrameData3d> &_linkFrameData);
208213

209214
/// \brief Update collision components from physics simulation
@@ -237,6 +242,11 @@ class ignition::gazebo::systems::PhysicsPrivate
237242
/// after a physics step.
238243
public: std::unordered_map<Entity, ignition::math::Pose3d> linkWorldPoses;
239244

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+
240250
/// \brief Keep track of non-static model world poses. Since non-static
241251
/// models may not move on a given iteration, we want to keep track of the
242252
/// most recent model world pose change that took place.
@@ -1178,6 +1188,7 @@ void PhysicsPrivate::RemovePhysicsEntities(const EntityComponentManager &_ecm)
11781188
this->topLevelModelMap.erase(childLink);
11791189
this->staticEntities.erase(childLink);
11801190
this->linkWorldPoses.erase(childLink);
1191+
this->canonicalLinkModelTracker.RemoveLink(childLink);
11811192
}
11821193

11831194
for (const auto &childJoint :
@@ -1835,13 +1846,13 @@ ignition::math::Pose3d PhysicsPrivate::RelativePose(const Entity &_from,
18351846
}
18361847

18371848
//////////////////////////////////////////////////
1838-
std::unordered_map<Entity, physics::FrameData3d> PhysicsPrivate::ChangedLinks(
1849+
std::map<Entity, physics::FrameData3d> PhysicsPrivate::ChangedLinks(
18391850
EntityComponentManager &_ecm,
18401851
const ignition::physics::ForwardStep::Output &_updatedLinks)
18411852
{
18421853
IGN_PROFILE("Links Frame Data");
18431854

1844-
std::unordered_map<Entity, physics::FrameData3d> linkFrameData;
1855+
std::map<Entity, physics::FrameData3d> linkFrameData;
18451856

18461857
// Check to see if the physics engine gave a list of changed poses. If not, we
18471858
// 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(
19121923

19131924
//////////////////////////////////////////////////
19141925
void PhysicsPrivate::UpdateSim(EntityComponentManager &_ecm,
1915-
const std::unordered_map<Entity, physics::FrameData3d> &_linkFrameData)
1926+
const std::map<Entity, physics::FrameData3d> &_linkFrameData)
19161927
{
19171928
IGN_PROFILE("PhysicsPrivate::UpdateSim");
19181929

19191930
IGN_PROFILE_BEGIN("Models");
19201931

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);
19321934

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+
}
19441964

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+
}
19872006

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+
}
19922011
IGN_PROFILE_END();
19932012

19942013
// Link poses, velocities...

0 commit comments

Comments
 (0)