Skip to content

Commit

Permalink
Add GeometryRevision. (#14196)
Browse files Browse the repository at this point in the history
* Add GeometryVersion.

Resolves #13176. GeometryState owns a GeometryVersion that enables a
easy query when the roles of the underlying geometries change.
Downstream systems may query the version through SceneGraphInspector.
  • Loading branch information
xuchenhan-tri committed Oct 23, 2020
1 parent 6369115 commit 81aebc7
Show file tree
Hide file tree
Showing 12 changed files with 727 additions and 16 deletions.
16 changes: 15 additions & 1 deletion bindings/pydrake/geometry_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -488,7 +488,9 @@ void DoScalarDependentDefinitions(py::module m, T) {
py_rvp::reference_internal, py::arg("geometry_id"),
cls_doc.GetPerceptionProperties.doc)
.def("CloneGeometryInstance", &Class::CloneGeometryInstance,
py::arg("geometry_id"), cls_doc.CloneGeometryInstance.doc);
py::arg("geometry_id"), cls_doc.CloneGeometryInstance.doc)
.def("geometry_version", &Class::geometry_version,
py_rvp::reference_internal, cls_doc.geometry_version.doc);
}

// SceneGraph
Expand Down Expand Up @@ -1113,6 +1115,18 @@ void DoScalarIndependentDefinitions(py::module m) {
.def(py::init(), doc.GeometrySet.ctor.doc);
}

// GeometryVersion
{
using Class = GeometryVersion;
constexpr auto& cls_doc = doc.GeometryVersion;
py::class_<Class> cls(m, "GeometryVersion", cls_doc.doc);
cls.def(py::init<const GeometryVersion&>(), py::arg("other"),
"Creates a copy of the GeometryVersion.")
.def("IsSameAs", &Class::IsSameAs, py::arg("other"), py::arg("role"),
cls_doc.IsSameAs.doc);
DefCopyAndDeepCopy(&cls);
}

// ProximityProperties
{
py::class_<ProximityProperties, GeometryProperties> cls(
Expand Down
22 changes: 22 additions & 0 deletions bindings/pydrake/test/geometry_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,8 @@ def test_scene_graph_api(self, T):
self.assertIsInstance(
inspector.GetPoseInFrame(geometry_id=global_geometry),
RigidTransform_[float])
self.assertIsInstance(inspector.geometry_version(),
mut.GeometryVersion)

# Check AssignRole bits.
proximity = mut.ProximityProperties()
Expand Down Expand Up @@ -367,6 +369,26 @@ def test_geometry_instance_api(self):
self.assertIsInstance(geometry.perception_properties(),
mut.PerceptionProperties)

def test_geometry_version_api(self):
SceneGraph = mut.SceneGraph_[float]
scene_graph = SceneGraph()
inspector = scene_graph.model_inspector()
version0 = inspector.geometry_version()
version1 = copy.deepcopy(version0)
self.assertTrue(version0.IsSameAs(other=version1,
role=mut.Role.kProximity))
self.assertTrue(version0.IsSameAs(other=version1,
role=mut.Role.kPerception))
self.assertTrue(version0.IsSameAs(other=version1,
role=mut.Role.kIllustration))
version2 = mut.GeometryVersion(other=version0)
self.assertTrue(version0.IsSameAs(other=version2,
role=mut.Role.kProximity))
self.assertTrue(version0.IsSameAs(other=version2,
role=mut.Role.kPerception))
self.assertTrue(version0.IsSameAs(other=version2,
role=mut.Role.kIllustration))

def test_rgba_api(self):
r, g, b, a = 0.75, 0.5, 0.25, 1.
color = mut.Rgba(r=r, g=g, b=b)
Expand Down
20 changes: 20 additions & 0 deletions geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ drake_cc_package_library(
":geometry_roles",
":geometry_set",
":geometry_state",
":geometry_version",
":geometry_visualization",
":internal_frame",
":internal_geometry",
Expand Down Expand Up @@ -130,6 +131,17 @@ drake_cc_library(
],
)

drake_cc_library(
name = "geometry_version",
srcs = ["geometry_version.cc"],
hdrs = ["geometry_version.h"],
deps = [
":geometry_roles",
"//common:essential",
"//common:identifier",
],
)

drake_cc_library(
name = "geometry_roles",
srcs = ["geometry_roles.cc"],
Expand Down Expand Up @@ -157,6 +169,7 @@ drake_cc_library(
":geometry_index",
":geometry_instance",
":geometry_set",
":geometry_version",
":internal_frame",
":internal_geometry",
":proximity_engine",
Expand Down Expand Up @@ -348,6 +361,13 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "geometry_version_test",
deps = [
":geometry_version",
],
)

drake_cc_googletest(
name = "geometry_set_test",
deps = [
Expand Down
28 changes: 25 additions & 3 deletions geometry/geometry_state.cc
Original file line number Diff line number Diff line change
Expand Up @@ -690,6 +690,7 @@ void GeometryState<T>::AssignRole(SourceId source_id, GeometryId geometry_id,
InternalGeometry& geometry =
ValidateRoleAssign(source_id, geometry_id, Role::kProximity, assign);

geometry_version_.modify_proximity();
switch (assign) {
case RoleAssign::kNew:
geometry.SetRole(std::move(properties));
Expand Down Expand Up @@ -800,6 +801,11 @@ void GeometryState<T>::AssignRole(SourceId source_id, GeometryId geometry_id,
"Perception role assigned to geometry {}, but no renderer accepted it",
geometry_id);
}
if (added_to_renderer) {
// Increment version number only if some renderer picks up the role
// assignment.
geometry_version_.modify_perception();
}
}

template <typename T>
Expand Down Expand Up @@ -833,6 +839,8 @@ void GeometryState<T>::AssignRole(SourceId source_id, GeometryId geometry_id,
InternalGeometry& geometry =
ValidateRoleAssign(source_id, geometry_id, Role::kIllustration, assign);

geometry_version_.modify_illustration();

geometry.SetRole(std::move(properties));
}

Expand Down Expand Up @@ -924,6 +932,8 @@ void GeometryState<T>::ExcludeCollisionsWithin(const GeometrySet& set) {
std::unordered_set<GeometryId> anchored;
CollectIds(set, &dynamic, &anchored);

geometry_version_.modify_proximity();

geometry_engine_->ExcludeCollisionsWithin(dynamic, anchored);
}

Expand All @@ -936,6 +946,9 @@ void GeometryState<T>::ExcludeCollisionsBetween(const GeometrySet& setA,
std::unordered_set<GeometryId> dynamic2;
std::unordered_set<GeometryId> anchored2;
CollectIds(setB, &dynamic2, &anchored2);

geometry_version_.modify_proximity();

geometry_engine_->ExcludeCollisionsBetween(dynamic1, anchored1, dynamic2,
anchored2);
}
Expand All @@ -949,17 +962,23 @@ void GeometryState<T>::AddRenderer(
}
render::RenderEngine* render_engine = renderer.get();
render_engines_[name] = move(renderer);
bool accepted = false;
for (auto& id_geo_pair : geometries_) {
InternalGeometry& geometry = id_geo_pair.second;
if (geometry.has_perception_role()) {
const GeometryId id = id_geo_pair.first;
const PerceptionProperties* properties = geometry.perception_properties();
DRAKE_DEMAND(properties != nullptr);
render_engine->RegisterVisual(id, geometry.shape(), *properties,
RigidTransformd(geometry.X_FG()),
geometry.is_dynamic());
accepted |= render_engine->RegisterVisual(
id, geometry.shape(), *properties,
RigidTransformd(geometry.X_FG()), geometry.is_dynamic());
}
}
// Increment version number if any geometry is registered to the new
// renderer.
if (accepted) {
geometry_version_.modify_perception();
}
}

template <typename T>
Expand Down Expand Up @@ -1332,6 +1351,7 @@ bool GeometryState<T>::RemoveFromRendererUnchecked(
// The engine has reported the belief that it has geometry `id`. Therefore,
// removal should report true.
DRAKE_DEMAND(engine->RemoveGeometry(id) == true);
geometry_version_.modify_perception();
return true;
}
return false;
Expand All @@ -1348,6 +1368,7 @@ bool GeometryState<T>::RemoveProximityRole(GeometryId geometry_id) {
// Geometry *is* registered; do the work to remove it.
geometry_engine_->RemoveGeometry(geometry_id, geometry->is_dynamic());
geometry->RemoveProximityRole();
geometry_version_.modify_proximity();
return true;
}

Expand All @@ -1360,6 +1381,7 @@ bool GeometryState<T>::RemoveIllustrationRole(GeometryId geometry_id) {
if (!geometry->has_illustration_role()) return false;

geometry->RemoveIllustrationRole();
geometry_version_.modify_illustration();
return true;
}

Expand Down
14 changes: 11 additions & 3 deletions geometry/geometry_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include "drake/geometry/geometry_index.h"
#include "drake/geometry/geometry_roles.h"
#include "drake/geometry/geometry_set.h"
#include "drake/geometry/geometry_version.h"
#include "drake/geometry/internal_frame.h"
#include "drake/geometry/internal_geometry.h"
#include "drake/geometry/proximity_engine.h"
Expand Down Expand Up @@ -66,7 +67,7 @@ using FrameIdSet = std::unordered_set<FrameId>;
template <typename T>
class GeometryState {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(GeometryState)
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(GeometryState);

/** An object that represents the range of FrameId values in the state. It
is used in range-based for loops to iterate through registered frames. */
Expand Down Expand Up @@ -130,6 +131,10 @@ class GeometryState {
/** Implementation of SceneGraphInspector::GetCollisionCandidates(). */
std::set<std::pair<GeometryId, GeometryId>> GetCollisionCandidates() const;

/** Implementation of SceneGraphInspector::GetGeometryVersion(). */
const GeometryVersion& geometry_version() const {
return geometry_version_;
}
//@}

/** @name Sources and source-related data */
Expand Down Expand Up @@ -371,7 +376,6 @@ class GeometryState {
d) the context has already been allocated. */
int RemoveFromRenderer(const std::string& renderer_name, SourceId source_id,
GeometryId geometry_id);

//@}

//----------------------------------------------------------------------------
Expand Down Expand Up @@ -567,7 +571,8 @@ class GeometryState {
geometries_(source.geometries_),
frame_index_to_id_map_(source.frame_index_to_id_map_),
geometry_engine_(std::move(source.geometry_engine_->ToAutoDiffXd())),
render_engines_(source.render_engines_) {
render_engines_(source.render_engines_),
geometry_version_(source.geometry_version_) {
auto convert_pose_vector = [](const std::vector<math::RigidTransform<U>>& s,
std::vector<math::RigidTransform<T>>* d) {
std::vector<math::RigidTransform<T>>& dest = *d;
Expand Down Expand Up @@ -851,6 +856,9 @@ class GeometryState {
// The collection of all registered renderers.
std::unordered_map<std::string, copyable_unique_ptr<render::RenderEngine>>
render_engines_;

// The version for this geometry data.
GeometryVersion geometry_version_;
};
} // namespace geometry
} // namespace drake
37 changes: 37 additions & 0 deletions geometry/geometry_version.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
#include "drake/geometry/geometry_version.h"

namespace drake {
namespace geometry {
bool GeometryVersion::IsSameAs(const GeometryVersion& other, Role role) const {
switch (role) {
case Role::kUnassigned:
throw std::logic_error(
"Trying to compare the version of unassigned roles.");
case Role::kProximity:
return proximity_version_id_ == other.proximity_version_id_;
case Role::kIllustration:
return illustration_version_id_ == other.illustration_version_id_;
case Role::kPerception:
return perception_version_id_ == other.perception_version_id_;
}
DRAKE_UNREACHABLE();
}

GeometryVersion::GeometryVersion()
: proximity_version_id_(RoleVersionId::get_new_id()),
perception_version_id_(RoleVersionId::get_new_id()),
illustration_version_id_(RoleVersionId::get_new_id()) {}

void GeometryVersion::modify_proximity() {
proximity_version_id_ = RoleVersionId::get_new_id();
}

void GeometryVersion::modify_perception() {
perception_version_id_ = RoleVersionId::get_new_id();
}

void GeometryVersion::modify_illustration() {
illustration_version_id_ = RoleVersionId::get_new_id();
}
} // namespace geometry
} // namespace drake
66 changes: 66 additions & 0 deletions geometry/geometry_version.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
#pragma once

#include "drake/common/drake_copyable.h"
#include "drake/common/identifier.h"
#include "drake/geometry/geometry_roles.h"

namespace drake {
namespace geometry {
/**
A version numbering class that reports revisions of SceneGraph's geometric data.
Other Systems can use this version number to perform updates when they detect
changes to the geometric data they consume. The version of the geometry data is
made available through SceneGraphInspector.
The geometry data is partitioned by geometric role and have independent role
version values. Some of SceneGraph's API (as variously documented) will cause
one or more role versions to change. This class provides the API `IsSameAs`
that takes another GeometryVersion as well as a Role to help detect whether the
provided role of the geometries may have changed. For example:
@code
// Downstream system holds an instance of GeometryVersion `old_version` as a
// reference to compare against.
// Get the version under test from SceneGraphInspector.
const GeometryVersion& test_version = scene_graph_inspector.geometry_version();
// Determine if two versions have the same proximity data.
bool same_proximity = old_version.IsSameAs(test_version, Role::kProximity);
@endcode
*/
class GeometryVersion {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(GeometryVersion);

/** Returns true if `this` GeometryVersion has the same `role`
version as the `other` GeometryVersion. */
bool IsSameAs(const GeometryVersion& other, Role role) const;

private:
using RoleVersionId = Identifier<class RoleVersionTag>;
/* Only GeometryState can update the role versions and construct
GeometryVersion from scratch. Downstream systems should obtain a reference
through the API provided by SceneGraphInspector if they want the version.
They then may choose to retain a copy if needed. */
template <typename T>
friend class GeometryState;

/* Facilitates testing. */
friend class GeometryVersionTest;

/* Create unique version id for all roles so that the new geometry version
unique. */
GeometryVersion();

void modify_proximity();

void modify_perception();

void modify_illustration();

RoleVersionId proximity_version_id_;
RoleVersionId perception_version_id_;
RoleVersionId illustration_version_id_;
};
} // namespace geometry
} // namespace drake
Loading

0 comments on commit 81aebc7

Please sign in to comment.