Skip to content

Commit

Permalink
Introduce preliminary elements for the RenderEngine
Browse files Browse the repository at this point in the history
1. Introduces the necessary components the RenderEngine will exercise.
  - RenderIndex
  - CameraProperties
2. Introduces and documents the Perception role (although exercising it
   will cause runtime errors).
  • Loading branch information
SeanCurtis-TRI committed Mar 26, 2019
1 parent 99121d5 commit 63b7e03
Show file tree
Hide file tree
Showing 5 changed files with 91 additions and 0 deletions.
2 changes: 2 additions & 0 deletions geometry/geometry_index.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
namespace drake {
namespace geometry {

/** Type used to locate any geometry in the render engine. */
using RenderIndex = TypeSafeIndex<class RenderTag>;

/** Index used to identify a geometry in the proximity engine. The same index
type applies to both anchored and dynamic geometries. They are distinguished
Expand Down
2 changes: 2 additions & 0 deletions geometry/geometry_roles.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@ std::string to_string(const Role& role) {
switch (role) {
case Role::kProximity:
return "proximity";
case Role::kPerception:
return "perception";
case Role::kIllustration:
return "illustration";
case Role::kUnassigned:
Expand Down
25 changes: 25 additions & 0 deletions geometry/geometry_roles.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@ namespace geometry {
- Display the progress of an interactive simulation of the arm in a GUI-based
visualization tool.
- Simulate a perception system which estimates arm state based on RGB images
of the arm.
- Compute contact forces between the virtual arm and its virtual environment.
- Find clearances between objects.
- Simulate what a camera or other sensor reports when exposed to the simulated
Expand Down Expand Up @@ -70,6 +72,8 @@ namespace geometry {
Drake partitions its geometry operations into classes (in the non-C++ sense of
the word) and defines a unique role for each class of operations.
<!-- TODO(SeanCurtis-TRI): Can we come up with a better name than "proximity"
akin to "Perception" and "Illustration"? -->
- __Proximity role__: these are the operations that are related to
evaluations of the signed distance between two geometries. When the
objects are separated, the distance is positive, when penetrating, the
Expand All @@ -90,6 +94,11 @@ namespace geometry {
can be requested from SceneGraph to, e.g., calculate forces. This role is
unique in this regard -- the geometry parameters for the other roles
affect the result of the geometric operation.
- __Perception role__: these are the operations that contribute to sensor
simulation. In other words, what can be seen? Typically, these are meshes
of medium to high fidelity (depending on the fidelity of the sensor). The
properties are models of the real world object's optical properties (its
color, shininess, opacity, etc.)
- __Illustration role__: these are the operations that connect drake to some
external visualizers. The intent is that geometries with this role don't
contribute to system calculations, they provide the basis for visualizing,
Expand All @@ -104,6 +113,7 @@ namespace geometry {
identifier (see SceneGraph::AssignRole()). The set _can_ be empty. Each
role has a specific property set associated with it:
- __Proximity role__: ProximityProperties
- __Perception role__: PerceptionProperties
- __Illustration role__: IllustrationProperties
Even for a single role, different consumers of a geometry may use different
Expand Down Expand Up @@ -145,6 +155,20 @@ class ProximityProperties final : public GeometryProperties {
ProximityProperties() = default;
};

/** The set of properties for geometry used in a "perception" role.
Examples of functionality that depends on the perception role:
- n/a
*/
class PerceptionProperties final : public GeometryProperties{
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(PerceptionProperties);
// TODO(SeanCurtis-TRI): Should this have a render label built in?

// TODO(SeanCurtis-TRI): Consider adding PerceptionIndex to this.
PerceptionProperties() = default;
};

/** The set of properties for geometry used in an "illustration" role.
Examples of functionality that depends on the illustration role:
Expand All @@ -163,6 +187,7 @@ enum class Role {
kUnassigned = 0x0,
kProximity = 0x1,
kIllustration = 0x2,
kPerception = 0x4
};

/** @name Geometry role to string conversions
Expand Down
2 changes: 2 additions & 0 deletions geometry/internal_geometry.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@ bool InternalGeometry::has_role(Role role) const {
return has_proximity_role();
case Role::kIllustration:
return has_illustration_role();
case Role::kPerception:
throw std::logic_error("Unsupported internal geometry role: perception");
case Role::kUnassigned:
return !(has_proximity_role() || has_illustration_role());
}
Expand Down
60 changes: 60 additions & 0 deletions geometry/render/camera_properties.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
#pragma once

#include <memory>
#include <string>
#include <utility>

namespace drake {
namespace geometry {
namespace render {

// TODO(SeanCurtis-TRI): Allow for configuring the intrinsic matrix directly
// with a projection matrix.
/** The intrinsic properties for a render camera. The render system
uses a reduced set of intrinsic parameters by making some simplifying
assumptions:
- Zero skew coefficient between the x- and y-axes.
- The camera's principal point lies in the center of the image.
The focal length is inferred by the sensor format (width and height) and the
field of view along the y-axis. */
struct CameraProperties {
CameraProperties(int width_in, int height_in, double fov_y_in,
std::string renderer_name_in)
: width(width_in),
height(height_in),
fov_y(fov_y_in),
renderer_name(std::move(renderer_name_in)) {}

int width{}; ///< The width of the image (in pixels) to be rendered.
int height{}; ///< The height of the image (in pixels) to be rendered.
double fov_y{}; ///< The camera's vertical field of view (in radians).
std::string renderer_name; ///< The name of the renderer to use.
};

/** The intrinsic properties for a render _depth_ camera. Consists of all of the
intrinsic properties of the render camera but extended with additional
depth-specific parameters.
@see CameraProperties */
struct DepthCameraProperties : public CameraProperties {
DepthCameraProperties(int width_in, int height_in, double fov_y_in,
std::string renderer_name_in, double z_near_in,
double z_far_in)
: CameraProperties(width_in, height_in, fov_y_in,
std::move(renderer_name_in)),
z_near(z_near_in),
z_far(z_far_in) {}

double z_near{}; ///< The minimum reportable depth value. All surfaces closer
///< than this distance, saturate to this value.
double z_far{}; ///< The maximum reportable depth value. All surfaces
///< farther than this distance, saturate to this value.
};

// TODO(SeanCurtis-TRI): Add properties for structured-light depth sensor which
// includes offsets from camera pose for both the emitter and sensor.

} // namespace render
} // namespace geometry
} // namespace drake

0 comments on commit 63b7e03

Please sign in to comment.