Skip to content

Commit

Permalink
Extend public API to provide ability to assign roles.
Browse files Browse the repository at this point in the history
This introduces a parallel API for registering geometry:
Register*WithoutRole(). Previous commits had introduced roles
internally and all geometries were registered with both proximity
and illustration roles by default. This alternate API registers
the geometry with the same effect, but without any default roles
assigned.

The parallel API will be used to migrate all the call sites over
to the new paradigm (of having to assign roles at the registration
site). Once those have been moved, the old API will be replaced
with the new (and names will be swapped).

The majority of the new code is in the geometry state unit tests. In
addition to testing the new AssignRole() methods, Role-dependent
count methods, and role assignment from geometry instances, it also
includes new unit tests on old code that is now impacted by roles (e.g.,
collision filtering).
  • Loading branch information
SeanCurtis-TRI committed Dec 7, 2018
1 parent 9482368 commit f6a8524
Show file tree
Hide file tree
Showing 12 changed files with 857 additions and 106 deletions.
1 change: 1 addition & 0 deletions geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,7 @@ drake_cc_library(
hdrs = ["geometry_instance.h"],
deps = [
":geometry_ids",
":geometry_roles",
":materials",
":shape_specification",
":utilities",
Expand Down
50 changes: 47 additions & 3 deletions geometry/geometry_instance.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,10 @@

#include "drake/common/copyable_unique_ptr.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_optional.h"
#include "drake/common/eigen_types.h"
#include "drake/geometry/geometry_ids.h"
#include "drake/geometry/geometry_roles.h"
#include "drake/geometry/shape_specification.h"
#include "drake/geometry/visual_material.h"

Expand Down Expand Up @@ -104,7 +106,7 @@ class GeometryInstance {
instantiation of %GeometryInstance will contain a unique id value. The id
value is preserved across copies. After successfully registering this
%GeometryInstance, this id will serve as the identifier for the registered
representation as well. */
representation as well. */
GeometryId id() const { return id_; }

const Isometry3<double>& pose() const { return X_PG_; }
Expand All @@ -115,14 +117,52 @@ class GeometryInstance {
return *shape_;
}

/** Releases the shape from the instance. */
/** Releases the shape from the instance. */
std::unique_ptr<Shape> release_shape() { return std::move(shape_); }

const VisualMaterial& visual_material() const { return visual_material_; }

/** Returns the *canonicalized* name for the instance. */
/** Returns the *canonicalized* name for the instance. */
const std::string& name() const { return name_; }

/** Sets the proximity properties for the given instance. */
void set_proximity_properties(ProximityProperties properties) {
proximity_properties_ = std::move(properties);
}

/** Sets the illustration properties for the given instance. */
void set_illustration_properties(IllustrationProperties properties) {
illustration_props_ = std::move(properties);
}

/** Returns a pointer to the geometry's mutable proximity properties (if they
are defined). Nullptr otherwise. */
ProximityProperties* mutable_proximity_properties() {
if (proximity_properties_) return &*proximity_properties_;
return nullptr;
}

/** Returns a pointer to the geometry's const proximity properties (if they
are defined). Nullptr otherwise. */
const ProximityProperties* proximity_properties() const {
if (proximity_properties_) return &*proximity_properties_;
return nullptr;
}

/** Returns a pointer to the geometry's mutable illustration properties (if
they are defined). Nullptr otherwise. */
IllustrationProperties* mutable_illustration_properties() {
if (illustration_props_) return &*illustration_props_;
return nullptr;
}

/** Returns a pointer to the geometry's const illustration properties (if
they are defined). Nullptr otherwise. */
const IllustrationProperties* illustration_properties() const {
if (illustration_props_) return &*illustration_props_;
return nullptr;
}

private:
// The *globally* unique identifier for this instance. It is functionally
// const (i.e. defined in construction) but not marked const to allow for
Expand All @@ -140,6 +180,10 @@ class GeometryInstance {

// The "rendering" material -- e.g., OpenGl contexts and the like.
VisualMaterial visual_material_;
// Optional properties.
optional<ProximityProperties> proximity_properties_{nullopt};
optional<IllustrationProperties> illustration_props_{nullopt};
};

} // namespace geometry
} // namespace drake
13 changes: 6 additions & 7 deletions geometry/geometry_roles.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,8 +98,10 @@ namespace geometry {
representations of real-world object surfaces. The properties associated
with this role are those necessary to draw the illustration.
Role assignment is achieved by assigning as set of role-related _properties_
to a geometry (see SceneGraph::AssignRole()). The set _can_ be empty. Each
Role assignment is achieved by assigning a set of role-related _properties_
to a geometry. The properties can either be assigned to the GeometryInstance
prior to registration, or after registration via the registered geometry's
identifier (see SceneGraph::AssignRole()). The set _can_ be empty. Each
role has a specific property set associated with it:
- __Proximity role__: ProximityProperties
- __Illustration role__: IllustrationProperties
Expand Down Expand Up @@ -127,10 +129,7 @@ namespace geometry {
Generally, any code that is dependent on geometry roles, should document the
type of role that it depends on, and the properties (if any) associated with
that role that it requires/prefers.
Roles are assigned during geometry registration (see
SceneGraph::AssignRole()). */
that role that it requires/prefers. */

/** The set of properties for geometry used in a _proximity_ role.
Expand Down Expand Up @@ -169,7 +168,7 @@ enum class Role {
/** @name Geometry role to string conversions
These are simply convenience functions for converting the Role enumeration into
a human-readable string. */
a human-readable string. */
//@{

std::string to_string(const Role& role);
Expand Down
159 changes: 134 additions & 25 deletions geometry/geometry_state.cc
Original file line number Diff line number Diff line change
Expand Up @@ -392,6 +392,37 @@ template <typename T>
GeometryId GeometryState<T>::RegisterGeometry(
SourceId source_id, FrameId frame_id,
std::unique_ptr<GeometryInstance> geometry) {
// Detects if the geometry instance has already been assigned properties and
// prepares defaults for assignment if not.
optional<IllustrationProperties> illustration;
optional<ProximityProperties> proximity;

// Any roles defined on the geometry instance propagate through automatically.
if (geometry != nullptr) {
if (!geometry->proximity_properties()) {
// NOTE: Default proximity properties have no values.
proximity.emplace();
}
if (!geometry->illustration_properties()) {
illustration.emplace();
illustration->AddProperty("phong", "diffuse",
geometry->visual_material().diffuse());
}
}

GeometryId geometry_id = RegisterGeometryWithoutRole(source_id, frame_id,
std::move(geometry));

if (proximity) AssignRole(source_id, geometry_id, *proximity);
if (illustration) AssignRole(source_id, geometry_id, *illustration);

return geometry_id;
}

template <typename T>
GeometryId GeometryState<T>::RegisterGeometryWithoutRole(
SourceId source_id, FrameId frame_id,
std::unique_ptr<GeometryInstance> geometry) {
if (geometry == nullptr) {
throw std::logic_error(
"Registering null geometry to frame " + to_string(frame_id) +
Expand Down Expand Up @@ -443,11 +474,16 @@ GeometryId GeometryState<T>::RegisterGeometry(
geometry->pose(), index,
geometry->visual_material()));

// NOTE: This is a temporary expedient to maintain backwards compatibility;
// all registered geometries implicitly have proximity *and* visualization
// roles. This maintains the implicit semantics until the API is changed.
// The assignment of the illustration role is handled in the constructor.
AssignRole(source_id, geometry_id, ProximityProperties());
// Any roles defined on the geometry instance propagate through automatically.
if (geometry->proximity_properties()) {
AssignRole(source_id, geometry_id,
std::move(*geometry->mutable_proximity_properties()));
}

if (geometry->illustration_properties()) {
AssignRole(source_id, geometry_id,
std::move(*geometry->mutable_illustration_properties()));
}

return geometry_id;
}
Expand Down Expand Up @@ -497,6 +533,61 @@ GeometryId GeometryState<T>::RegisterGeometryWithParent(
return new_id;
}

template <typename T>
GeometryId GeometryState<T>::RegisterGeometryWithParentWithoutRole(
SourceId source_id, GeometryId parent_id,
std::unique_ptr<GeometryInstance> geometry) {
// NOTE: This is currently just a copy-and-paste of the
// RegisterGeometryWithParent() method with the call to RegisterGeometry()
// changed. In a few more PRs, this will drop back down to only a single
// variant.

// There are three error conditions in the doxygen:.
// 1. geometry == nullptr,
// 2. source_id is not a registered source, and
// 3. parent_id doesn't belong to source_id.
//
// Only #1 is tested directly. #2 and #3 are tested implicitly during the act
// of registering the geometry.

if (geometry == nullptr) {
throw std::logic_error(
"Registering null geometry to geometry " + to_string(parent_id) +
", on source " + to_string(source_id) + ".");
}

// This confirms that parent_id exists at all.
InternalGeometry& parent_geometry =
GetMutableValueOrThrow(parent_id, &geometries_);
FrameId frame_id = parent_geometry.frame_id();

// TODO(SeanCurtis-TRI): Revisit this post-hoc parent patching code for
// something more direct. See
// https://github.com/RobotLocomotion/drake/issues/10147.

// This implicitly confirms that source_id is registered (condition #2) and
// that frame_id belongs to source_id. By construction, parent_id must
// belong to the same source as frame_id, so this tests condition #3.
GeometryId new_id = RegisterGeometryWithoutRole(source_id, frame_id,
move(geometry));

// RegisterGeometry stores X_PG into X_FG_ (having assumed that the
// parent was a frame). The following code replaces the stored X_PG value with
// the semantically correct value X_FG by concatenating X_FP with X_PG.

// Transform pose relative to geometry, to pose relative to frame.
InternalGeometry& new_geometry = geometries_[new_id];
// The call to `RegisterGeometry()` above stashed the pose X_PG into the
// X_FG_ vector assuming the parent was the frame. Replace it by concatenating
// its pose in parent, with its parent's pose in frame. NOTE: the pose is no
// longer available from geometry because of the `move(geometry)`.
const Isometry3<double>& X_PG = new_geometry.X_FG();
const Isometry3<double>& X_FP = parent_geometry.X_FG();
new_geometry.set_geometry_parent(parent_id, X_FP * X_PG);
parent_geometry.add_child(new_id);
return new_id;
}

template <typename T>
GeometryId GeometryState<T>::RegisterAnchoredGeometry(
SourceId source_id,
Expand All @@ -505,6 +596,14 @@ GeometryId GeometryState<T>::RegisterAnchoredGeometry(
std::move(geometry));
}

template <typename T>
GeometryId GeometryState<T>::RegisterAnchoredGeometryWithoutRole(
SourceId source_id,
std::unique_ptr<GeometryInstance> geometry) {
return RegisterGeometryWithoutRole(source_id, InternalFrame::world_frame_id(),
std::move(geometry));
}

template <typename T>
void GeometryState<T>::RemoveGeometry(SourceId source_id,
GeometryId geometry_id) {
Expand Down Expand Up @@ -666,23 +765,33 @@ void GeometryState<T>::ExcludeCollisionsBetween(const GeometrySet& setA,
std::unordered_set<GeometryIndex> dynamic2;
std::unordered_set<GeometryIndex> anchored2;
CollectIndices(setB, &dynamic2, &anchored2);

geometry_engine_->ExcludeCollisionsBetween(dynamic1, anchored1, dynamic2,
anchored2);
}

template <typename T>
bool GeometryState<T>::CollisionFiltered(GeometryId id1, GeometryId id2) const {
std::string base_message =
"Can't report collision filter status between geometries " +
to_string(id1) + " and " + to_string(id2) + "; ";
const internal::InternalGeometry* geometry1 = GetGeometry(id1);
const internal::InternalGeometry* geometry2 = GetGeometry(id2);
if (geometry1 != nullptr && geometry2 != nullptr) {
return geometry_engine_->CollisionFiltered(
geometry1->index(), geometry1->is_dynamic(),
geometry2->index(), geometry2->is_dynamic());
if (geometry1->has_proximity_role() && geometry2->has_proximity_role()) {
return geometry_engine_->CollisionFiltered(
geometry1->index(), geometry1->is_dynamic(),
geometry2->index(), geometry2->is_dynamic());
}
if (geometry1->has_proximity_role()) {
throw std::logic_error(base_message + to_string(id2) +
" does not have a proximity role");
} else if (geometry2->has_proximity_role()) {
throw std::logic_error(base_message + to_string(id1) +
" does not have a proximity role");
} else {
throw std::logic_error(base_message + " neither id has a proximity role");
}
}
std::string base_message =
"Can't report collision filter status between geometries " +
to_string(id1) + " and " + to_string(id2) + "; ";
if (geometry1 != nullptr) {
throw std::logic_error(base_message + to_string(id2) +
" is not a valid geometry");
Expand Down Expand Up @@ -825,20 +934,20 @@ void GeometryState<T>::RemoveGeometryUnchecked(GeometryId geometry_id,
removed_index);
}

// Now remove the geometry from engines. In the future, base this on the
// _role_ of the geometry.
ProximityIndex proximity_index = geometry.proximity_index();
optional<GeometryIndex> moved_index = geometry_engine_->RemoveGeometry(
proximity_index, geometry.is_dynamic());
if (moved_index) {
// The geometry engine moved a geometry into the removed `proximity_index`.
// Update the state's knowledge of this.
GeometryId moved_id = geometry_index_to_id_map_[*moved_index];
if (geometry.is_dynamic()) {
swap(X_WG_[proximity_index],
X_WG_[geometries_[moved_id].proximity_index()]);
if (geometry.has_proximity_role()) {
ProximityIndex proximity_index = geometry.proximity_index();
optional<GeometryIndex> moved_index = geometry_engine_->RemoveGeometry(
proximity_index, geometry.is_dynamic());
if (moved_index) {
// The geometry engine moved a geometry into the removed
// `proximity_index`. Update the state's knowledge of this.
GeometryId moved_id = geometry_index_to_id_map_[*moved_index];
if (geometry.is_dynamic()) {
swap(X_WG_[proximity_index],
X_WG_[geometries_[moved_id].proximity_index()]);
}
geometries_[moved_id].set_proximity_index(proximity_index);
}
geometries_[moved_id].set_proximity_index(proximity_index);
}

if (caller == RemoveGeometryOrigin::kGeometry) {
Expand Down
Loading

0 comments on commit f6a8524

Please sign in to comment.