Skip to content

Commit

Permalink
[render] Patch a number of gaps in previous PRs preparatory to public…
Browse files Browse the repository at this point in the history
… API (RobotLocomotion#11597)

* Patch a number of gaps in previous PRs preparatory to public API

1. Simplify RenderLabelManager API and test; this leads to a better
   distribution of responsiblities between RenderLabelManager and
   SceneGraph.
2. GeometryInstance allows perception properties to be assigned prior to
   registration (GeometryState uses it) (add missing feature)
3. RemovePerceptionRole() had bad return value (bugfix)
4. RenderEngine::UpdateViewpoint() (as the name suggests) should *not* be
   const (design correction).
  • Loading branch information
SeanCurtis-TRI authored Jun 10, 2019
1 parent cbe797d commit 133f25a
Show file tree
Hide file tree
Showing 11 changed files with 147 additions and 100 deletions.
30 changes: 25 additions & 5 deletions geometry/geometry_instance.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,12 @@ class GeometryInstance {

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

/** Sets the perception properties for the given instance. */
void set_perception_properties(PerceptionProperties properties) {
perception_properties_ = std::move(properties);
}

/** Returns a pointer to the geometry's mutable proximity properties (if they
Expand All @@ -138,14 +143,28 @@ class GeometryInstance {
/** 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_;
if (illustration_properties_) return &*illustration_properties_;
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_;
if (illustration_properties_) return &*illustration_properties_;
return nullptr;
}

/** Returns a pointer to the geometry's mutable perception properties (if
they are defined). Nullptr otherwise. */
PerceptionProperties* mutable_perception_properties() {
if (perception_properties_) return &*perception_properties_;
return nullptr;
}

/** Returns a pointer to the geometry's const perception properties (if
they are defined). Nullptr otherwise. */
const PerceptionProperties* perception_properties() const {
if (perception_properties_) return &*perception_properties_;
return nullptr;
}

Expand All @@ -165,8 +184,9 @@ class GeometryInstance {
std::string name_;

// Optional properties.
optional<ProximityProperties> proximity_properties_{nullopt};
optional<IllustrationProperties> illustration_props_{nullopt};
optional<ProximityProperties> proximity_properties_{};
optional<IllustrationProperties> illustration_properties_{};
optional<PerceptionProperties> perception_properties_{};
};

} // namespace geometry
Expand Down
46 changes: 25 additions & 21 deletions geometry/geometry_state.cc
Original file line number Diff line number Diff line change
Expand Up @@ -576,6 +576,11 @@ GeometryId GeometryState<T>::RegisterGeometry(
std::move(*geometry->mutable_proximity_properties()));
}

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

return geometry_id;
}

Expand Down Expand Up @@ -814,7 +819,7 @@ int GeometryState<T>::RemoveRole(SourceId source_id, FrameId frame_id,
// geometry must belong to the same source as the parent frame.
if (frame_id != InternalFrame::world_frame_id() ||
BelongsToSource(geometry_id, source_id)) {
count += RemoveRoleUnchecked(geometry_id, role);
if (RemoveRoleUnchecked(geometry_id, role)) ++count;
}
}
return count;
Expand All @@ -833,7 +838,7 @@ int GeometryState<T>::RemoveRole(SourceId source_id, GeometryId geometry_id,
// One can't "remove" the unassigned role state.
if (role == Role::kUnassigned) return 0;

return RemoveRoleUnchecked(geometry_id, role);
return RemoveRoleUnchecked(geometry_id, role) ? 1 : 0;
}

template <typename T>
Expand All @@ -849,7 +854,7 @@ int GeometryState<T>::RemoveFromRenderer(const std::string& renderer_name,
// geometry must belong to the same source as the parent frame.
if (frame_id != InternalFrame::world_frame_id() ||
BelongsToSource(geometry_id, source_id)) {
count += RemoveFromRendererUnchecked(renderer_name, geometry_id);
if (RemoveFromRendererUnchecked(renderer_name, geometry_id)) ++count;
}
}
return count;
Expand All @@ -866,7 +871,7 @@ int GeometryState<T>::RemoveFromRenderer(const std::string& renderer_name,
"given source " + to_string(source_id) + ".");
}

return RemoveFromRendererUnchecked(renderer_name, geometry_id);
return RemoveFromRendererUnchecked(renderer_name, geometry_id) ? 1 : 0;
}

template <typename T>
Expand Down Expand Up @@ -1201,29 +1206,29 @@ void GeometryState<T>::AssignRoleInternal(SourceId source_id,
}

template <typename T>
int GeometryState<T>::RemoveRoleUnchecked(GeometryId geometry_id, Role role) {
bool GeometryState<T>::RemoveRoleUnchecked(GeometryId geometry_id, Role role) {
switch (role) {
case Role::kUnassigned:
// Can't remove unassigned; it's a no op.
return 0;
return false;
case Role::kProximity:
return RemoveProximityRole(geometry_id);
case Role::kIllustration:
return RemoveIllustrationRole(geometry_id);
case Role::kPerception:
return RemovePerceptionRole(geometry_id);
}
return 0;
return false;
}

template <typename T>
int GeometryState<T>::RemoveFromRendererUnchecked(
bool GeometryState<T>::RemoveFromRendererUnchecked(
const std::string& renderer_name, GeometryId id) {
internal::InternalGeometry* geometry = GetMutableGeometry(id);
optional<RenderIndex> render_index = geometry->render_index(renderer_name);

// This geometry is not registered with the named render engine.
if (!render_index) return 0;
if (!render_index) return false;

// It is registered with the render engine; do the work to remove it.
render::RenderEngine* engine = render_engines_[renderer_name].get_mutable();
Expand All @@ -1249,16 +1254,16 @@ int GeometryState<T>::RemoveFromRendererUnchecked(
moved_geometry.ClearRenderIndex(renderer_name);
moved_geometry.set_render_index(renderer_name, *render_index);
}
return 1;
return true;
}

template <typename T>
int GeometryState<T>::RemoveProximityRole(GeometryId geometry_id) {
bool GeometryState<T>::RemoveProximityRole(GeometryId geometry_id) {
internal::InternalGeometry* geometry = GetMutableGeometry(geometry_id);
DRAKE_DEMAND(geometry != nullptr);

// Geometry is not registered with the proximity engine.
if (!geometry->has_proximity_role()) return 0;
if (!geometry->has_proximity_role()) return false;

// Geometry *is* registered; do the work to remove it.
ProximityIndex proximity_index = geometry->proximity_index();
Expand Down Expand Up @@ -1292,38 +1297,37 @@ int GeometryState<T>::RemoveProximityRole(GeometryId geometry_id) {
dynamic_proximity_index_to_internal_map_.pop_back();
}
geometry->RemoveProximityRole();
return 1;
return true;
}

template <typename T>
int GeometryState<T>::RemoveIllustrationRole(GeometryId geometry_id) {
bool GeometryState<T>::RemoveIllustrationRole(GeometryId geometry_id) {
internal::InternalGeometry* geometry = GetMutableGeometry(geometry_id);
DRAKE_DEMAND(geometry != nullptr);

// Geometry has no illustration role.
if (!geometry->has_illustration_role()) return 0;
if (!geometry->has_illustration_role()) return false;

geometry->RemoveIllustrationRole();
return 1;
return true;
}

template <typename T>
int GeometryState<T>::RemovePerceptionRole(GeometryId geometry_id) {
bool GeometryState<T>::RemovePerceptionRole(GeometryId geometry_id) {
internal::InternalGeometry* geometry = GetMutableGeometry(geometry_id);
DRAKE_DEMAND(geometry != nullptr);

// Geometry has no perception role.
if (!geometry->has_perception_role()) return 0;
if (!geometry->has_perception_role()) return false;

// Geometry has a perception role; do the work to remove it from whichever
// render engines it happens to present in.
int count = 0;
for (auto& name_engine_pair : render_engines_) {
const std::string& engine_name = name_engine_pair.first;
count = RemoveFromRendererUnchecked(engine_name, geometry_id);
RemoveFromRendererUnchecked(engine_name, geometry_id);
}
geometry->RemovePerceptionRole();
return count;
return true;
}

template <typename T>
Expand Down
25 changes: 14 additions & 11 deletions geometry/geometry_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -620,22 +620,22 @@ class GeometryState {
void AssignRoleInternal(SourceId source_id, GeometryId geometry_id,
PropertyType properties, Role role);

// Removes the indicated `role` from the indicated geometry. Returns 1 if the
// geometry formerly had that role, and 0 if not. This does no checking on
// ownership.
// Attempts to remove the indicated `role` from the indicated geometry.
// Returns true if removed (false doesn't imply "failure", just nothing to
// remove). This does no checking on ownership.
// @pre geometry_id maps to a registered geometry.
int RemoveRoleUnchecked(GeometryId geometry_id, Role role);
bool RemoveRoleUnchecked(GeometryId geometry_id, Role role);

// Removes the geometry with the given `id` from the named renderer. Returns 1
// if the geometry formerly had been included in the renderer, 0 if not. This
// does no checking on ownership.
// Attempts to remove the geometry with the given `id` from the named
// renderer. Returns true if removed (false doesn't imply "failure", just
// nothing to remove). This does no checking on ownership.
// @pre geometry_id maps to a registered geometry.
int RemoveFromRendererUnchecked(const std::string& renderer_name,
bool RemoveFromRendererUnchecked(const std::string& renderer_name,
GeometryId id);

int RemoveProximityRole(GeometryId geometry_id);
int RemoveIllustrationRole(GeometryId geometry_id);
int RemovePerceptionRole(GeometryId geometry_id);
bool RemoveProximityRole(GeometryId geometry_id);
bool RemoveIllustrationRole(GeometryId geometry_id);
bool RemovePerceptionRole(GeometryId geometry_id);

// When performing an operation on a frame, the caller provides its source id
// and the id of the frame it owns as the operand. Generally, the validation
Expand Down Expand Up @@ -727,6 +727,9 @@ class GeometryState {
// the proximity engine.
// NOTE: There is no equivalent for anchored geometries because anchored
// geometries do not need updating.
// TODO(SeanCurtis-TRI): Move this into the proximity engine. Its presence
// here is an anachronism. Better yet, this will die when we make GeometryId
// the only identifier that moves between GeometryState and the engines.
std::vector<GeometryIndex> dynamic_proximity_index_to_internal_map_;

// ---------------------------------------------------------------------
Expand Down
2 changes: 1 addition & 1 deletion geometry/render/render_engine.h
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ class RenderEngine : public ShapeReifier {
@param X_WR The pose of renderer's viewpoint in the world coordinate
system. */
virtual void UpdateViewpoint(const math::RigidTransformd& X_WR) const = 0;
virtual void UpdateViewpoint(const math::RigidTransformd& X_WR) = 0;

/** Renders the registered geometry into the given color (rgb) image.
Expand Down
2 changes: 1 addition & 1 deletion geometry/render/render_engine_vtk.cc
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ RenderEngineVtk::RenderEngineVtk(const RenderEngineVtkParams& parameters)
InitializePipelines();
}

void RenderEngineVtk::UpdateViewpoint(const RigidTransformd& X_WC) const {
void RenderEngineVtk::UpdateViewpoint(const RigidTransformd& X_WC) {
vtkSmartPointer<vtkTransform> vtk_X_WC = ConvertToVtkTransform(X_WC);

for (const auto& pipeline : pipelines_) {
Expand Down
2 changes: 1 addition & 1 deletion geometry/render/render_engine_vtk.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class RenderEngineVtk final : public RenderEngine,
const RenderEngineVtkParams& parameters = RenderEngineVtkParams());

/** @see RenderEngine::UpdateViewpoint(). */
void UpdateViewpoint(const math::RigidTransformd& X_WR) const final;
void UpdateViewpoint(const math::RigidTransformd& X_WR) final;

/** @see RenderEngine::RenderColorImage(). */
void RenderColorImage(
Expand Down
9 changes: 0 additions & 9 deletions geometry/render/render_label_manager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -48,15 +48,6 @@ RenderLabel RenderLabelManager::GetRenderLabel(SourceId source_id,
}
}

vector<RenderLabelClass> RenderLabelManager::GetRenderLabelClasses() const {
vector<RenderLabelClass> classes;
for (auto it = name_label_map_.begin(); it != name_label_map_.end(); ++it) {
const RenderLabelClass& label_class = it->second;
classes.push_back(label_class);
}
return classes;
}

} // namespace internal
} // namespace render
} // namespace geometry
Expand Down
10 changes: 7 additions & 3 deletions geometry/render/render_label_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,13 @@ class RenderLabelManager {
/** Implementation of SceneGraph::GetRenderLabel(). */
RenderLabel GetRenderLabel(SourceId source_id, std::string class_name);

/** Provides a report of all the allocated RenderLabel values and their
semantic classes (in no particular order). */
std::vector<RenderLabelClass> GetRenderLabelClasses() const;
/** Returns the record of all allocated render labels and their semantic
classes. It is represented as a map from the _semantic name_ to the semantic
class's data. For semantic names that have been used by more than one source,
the semantic name will map to multiple semantic classes, distinguished by
their source id and RenderLabel value. */
const std::unordered_multimap<std::string, RenderLabelClass>&
render_label_classes() const { return name_label_map_; }

private:
friend class RenderLabelManagerTester;
Expand Down
41 changes: 0 additions & 41 deletions geometry/render/test/render_label_manager_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -177,47 +177,6 @@ GTEST_TEST(RenderLabelManagerTest, GetRenderLabel) {
"All \\d+ render labels have been allocated");
}

GTEST_TEST(RenderLabelManagerTest, GetRenderLabelClasses) {
SourceId manager_id = SourceId::get_new_id();
SourceId source1 = SourceId::get_new_id();
SourceId source2 = SourceId::get_new_id();

RenderLabelManager manager(manager_id);
std::vector<RenderLabelClass> expected_classes;
auto add_label = [&expected_classes, &manager](const std::string& name,
SourceId source_id) {
expected_classes.emplace_back(name, source_id,
manager.GetRenderLabel(source_id, name));
};
// Reserved labels.
expected_classes.emplace_back("empty", manager_id, RenderLabel::kEmpty);
expected_classes.emplace_back("unspecified", manager_id,
RenderLabel::kUnspecified);
expected_classes.emplace_back("dont_care", manager_id,
RenderLabel::kDontCare);
expected_classes.emplace_back("do_not_render", manager_id,
RenderLabel::kDoNotRender);
add_label("common", source1);
add_label("common", source2);
add_label("unique1", source1);
add_label("unique2", source2);

std::vector<RenderLabelClass> classes = manager.GetRenderLabelClasses();
EXPECT_EQ(classes.size(), expected_classes.size());

for (const auto& label_class : classes) {
bool found = false;
for (const auto& expected_class : expected_classes) {
if (label_class == expected_class) {
found = true;
break;
}
}
EXPECT_TRUE(found) << "Reported label class not found in expected classes: "
<< label_class;
}
}

} // namespace
} // namespace internal
} // namespace render
Expand Down
Loading

0 comments on commit 133f25a

Please sign in to comment.