Skip to content

Commit

Permalink
Cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
SeanCurtis-TRI committed Jun 19, 2019
1 parent 17824fa commit bdc10f5
Show file tree
Hide file tree
Showing 9 changed files with 40 additions and 44 deletions.
8 changes: 4 additions & 4 deletions geometry/geometry_state.cc
Original file line number Diff line number Diff line change
Expand Up @@ -938,8 +938,8 @@ template <typename T>
void GeometryState<T>::RenderColorImage(const render::CameraProperties& camera,
FrameId parent_frame,
const RigidTransformd& X_PC,
ImageRgba8U* color_image_out,
bool show_window) const {
bool show_window,
ImageRgba8U* color_image_out) const {
const RigidTransformd X_WC = GetDoubleWorldPose(parent_frame) * X_PC;
const render::RenderEngine& engine =
GetRenderEngineOrThrow(camera.renderer_name);
Expand All @@ -966,8 +966,8 @@ template <typename T>
void GeometryState<T>::RenderLabelImage(const render::CameraProperties& camera,
FrameId parent_frame,
const RigidTransformd& X_PC,
ImageLabel16I* label_image_out,
bool show_window) const {
bool show_window,
ImageLabel16I* label_image_out) const {
const RigidTransformd X_WC = GetDoubleWorldPose(parent_frame) * X_PC;
const render::RenderEngine& engine =
GetRenderEngineOrThrow(camera.renderer_name);
Expand Down
8 changes: 4 additions & 4 deletions geometry/geometry_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -493,8 +493,8 @@ class GeometryState {
void RenderColorImage(const render::CameraProperties& camera,
FrameId parent_frame,
const math::RigidTransformd& X_PC,
systems::sensors::ImageRgba8U* color_image_out,
bool show_window) const;
bool show_window,
systems::sensors::ImageRgba8U* color_image_out) const;

/** Implementation support for QueryObject::RenderDepthImage().
@pre All poses have already been updated. */
Expand All @@ -508,8 +508,8 @@ class GeometryState {
void RenderLabelImage(const render::CameraProperties& camera,
FrameId parent_frame,
const math::RigidTransformd& X_PC,
systems::sensors::ImageLabel16I* label_image_out,
bool show_window) const;
bool show_window,
systems::sensors::ImageLabel16I* label_image_out) const;

//@}

Expand Down
16 changes: 8 additions & 8 deletions geometry/query_object.cc
Original file line number Diff line number Diff line change
Expand Up @@ -118,14 +118,14 @@ template <typename T>
void QueryObject<T>::RenderColorImage(const CameraProperties& camera,
FrameId parent_frame,
const RigidTransformd& X_PC,
ImageRgba8U* color_image_out,
bool show_window) const {
bool show_window,
ImageRgba8U* color_image_out) const {
ThrowIfNotCallable();

FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.RenderColorImage(camera, parent_frame, X_PC, color_image_out,
show_window);
return state.RenderColorImage(camera, parent_frame, X_PC, show_window,
color_image_out);
}

template <typename T>
Expand All @@ -144,14 +144,14 @@ template <typename T>
void QueryObject<T>::RenderLabelImage(const CameraProperties& camera,
FrameId parent_frame,
const RigidTransformd& X_PC,
ImageLabel16I* label_image_out,
bool show_window) const {
bool show_window,
ImageLabel16I* label_image_out) const {
ThrowIfNotCallable();

FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.RenderLabelImage(camera, parent_frame, X_PC, label_image_out,
show_window);
return state.RenderLabelImage(camera, parent_frame, X_PC, show_window,
label_image_out);
}

template <typename T>
Expand Down
24 changes: 9 additions & 15 deletions geometry/query_object.h
Original file line number Diff line number Diff line change
Expand Up @@ -357,16 +357,10 @@ class QueryObject {
extrinsic and intrinsic properties and %QueryObject renders into the
provided image.
Eventually, there will be multiple renderers that can be invoked which vary
in the fidelity of the images they produce. Currently, only the low fidelity
renderer is implemented. Invocation on a higher level of fidelity will throw
an exception. As additional renderers get added, they will be engaged via
this same interface.
<!-- TODO(SeanCurtis-TRI): Currently, pose is requested as a transform of
double. This puts the burden on the caller to be compatible. Provide
specializations for AutoDiff and symbolic (the former extracts a
double-valued transform and the latter throws).
double-valued transform and the latter throws). -->
*/
//@{

Expand All @@ -376,13 +370,13 @@ class QueryObject {
@param camera The intrinsic properties of the camera.
@param parent_frame The id for the camera's parent frame.
@param X_PC The pose of the camera body in the world frame.
@param[out] color_image_out The rendered color image.
@param show_window If true, the render window will be displayed. */
@param show_window If true, the render window will be displayed.
@param[out] color_image_out The rendered color image. */
void RenderColorImage(const render::CameraProperties& camera,
FrameId parent_frame,
const math::RigidTransformd& X_PC,
systems::sensors::ImageRgba8U* color_image_out,
bool show_window) const;
bool show_window,
systems::sensors::ImageRgba8U* color_image_out) const;

/** Renders a depth image for the given `camera` posed with respect to the
indicated parent frame P.
Expand All @@ -406,13 +400,13 @@ class QueryObject {
@param camera The intrinsic properties of the camera.
@param parent_frame The id for the camera's parent frame.
@param X_PC The pose of the camera body in the world frame.
@param[out] label_image_out The rendered label image.
@param show_window If true, the render window will be displayed. */
@param show_window If true, the render window will be displayed.
@param[out] label_image_out The rendered label image. */
void RenderLabelImage(const render::CameraProperties& camera,
FrameId parent_frame,
const math::RigidTransformd& X_PC,
systems::sensors::ImageLabel16I* label_image_out,
bool show_window) const;
bool show_window,
systems::sensors::ImageLabel16I* label_image_out) const;

//@}

Expand Down
14 changes: 5 additions & 9 deletions geometry/scene_graph.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,10 @@ namespace geometry {
using render::RenderLabel;
using systems::Context;
using systems::InputPort;
using systems::LeafContext;
using systems::LeafSystem;
using systems::rendering::PoseBundle;
using systems::SystemOutput;
using systems::SystemSymbolicInspector;
using systems::SystemTypeTag;
using std::make_unique;
using std::unordered_map;
using std::vector;

namespace {
Expand Down Expand Up @@ -107,7 +103,7 @@ SceneGraph<T>::SceneGraph(const SceneGraph<U>& other) : SceneGraph() {
// time.
// Therefore, for SourceIds i and j, the if i > j, then the port indices for
// source i must all be greater than those for j.
std::vector<SourceId> source_ids;
vector<SourceId> source_ids;
for (const auto pair : other.input_source_ids_) {
source_ids.push_back(pair.first);
}
Expand Down Expand Up @@ -137,7 +133,7 @@ bool SceneGraph<T>::SourceIsRegistered(SourceId id) const {
}

template <typename T>
const systems::InputPort<T>& SceneGraph<T>::get_source_pose_port(
const InputPort<T>& SceneGraph<T>::get_source_pose_port(
SourceId id) const {
ThrowUnlessRegistered(id, "Can't acquire pose port for unknown source id: ");
return this->get_input_port(input_source_ids_.at(id).pose_port);
Expand Down Expand Up @@ -224,7 +220,7 @@ int SceneGraph<T>::RendererCount() const {
}

template <typename T>
std::vector<std::string> SceneGraph<T>::RegisteredRendererNames() const {
vector<std::string> SceneGraph<T>::RegisteredRendererNames() const {
return initial_state_->RegisteredRendererNames();
}

Expand Down Expand Up @@ -365,7 +361,7 @@ PoseBundle<T> SceneGraph<T>::MakePoseBundle() const {
// *model*.
// TODO(SeanCurtis-TRI): This happens *twice* now (once here and once in
// CalcPoseBundle); might be worth refactoring/caching it.
std::vector<FrameId> dynamic_frames;
vector<FrameId> dynamic_frames;
for (const auto& pair : g_state.frames_) {
const FrameId frame_id = pair.first;
if (frame_id == world_frame_id()) continue;
Expand Down Expand Up @@ -403,7 +399,7 @@ void SceneGraph<T>::CalcPoseBundle(const Context<T>& context,

// Collect only those frames that have illustration geometry -- based on the
// *model*.
std::vector<FrameId> dynamic_frames;
vector<FrameId> dynamic_frames;
for (const auto& pair : g_state.frames_) {
const FrameId frame_id = pair.first;
if (frame_id == world_frame_id()) continue;
Expand Down
2 changes: 1 addition & 1 deletion geometry/scene_graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -481,7 +481,7 @@ class SceneGraph final : public systems::LeafSystem<T> {
@param name The unique name of the renderer.
@param renderer The `renderer` to add.
@throws std::logic_error if the name is not unique, or geometry has already
been registered. */
been registered. */
void AddRenderer(std::string name,
std::unique_ptr<render::RenderEngine> renderer);

Expand Down
7 changes: 7 additions & 0 deletions geometry/test/geometry_state_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3391,6 +3391,13 @@ TEST_F(GeometryStateNoRendererTest, PerceptionRoleWithoutRenderer) {
0);
}

// TODO(SeanCurtis-TRI): The `Render*Image` interface is insufficiently tested.
// GeometryState is a thin wrapper on the render engine, but GeometryState is
// responsible for:
// 1. Confirming the parent frame is valid.
// 2. Updating the camera pose.
// 3. Calling the appropriate render engine.

} // namespace
} // namespace geometry
} // namespace drake
4 changes: 2 additions & 2 deletions geometry/test/query_object_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -190,15 +190,15 @@ TEST_F(QueryObjectTest, DefaultQueryThrows) {
RigidTransformd X_WC = RigidTransformd::Identity();
ImageRgba8U color;
EXPECT_DEFAULT_ERROR(default_object->RenderColorImage(
properties, FrameId::get_new_id(), X_WC, &color, false));
properties, FrameId::get_new_id(), X_WC, false, &color));

ImageDepth32F depth;
EXPECT_DEFAULT_ERROR(default_object->RenderDepthImage(
properties, FrameId::get_new_id(), X_WC, &depth));

ImageLabel16I label;
EXPECT_DEFAULT_ERROR(default_object->RenderLabelImage(
properties, FrameId::get_new_id(), X_WC, &label, false));
properties, FrameId::get_new_id(), X_WC, false, &label));

#undef EXPECT_DEFAULT_ERROR
}
Expand Down
1 change: 0 additions & 1 deletion geometry/test/scene_graph_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ using systems::rendering::PoseBundle;
using systems::System;
using std::make_unique;
using std::unique_ptr;
using std::unordered_map;

// Friend class for working with QueryObjects in a test context.
class QueryObjectTester {
Expand Down

0 comments on commit bdc10f5

Please sign in to comment.