Drake
Drake C++ Documentation
CameraConfig Struct Reference

Detailed Description

Configuration of a camera.

This covers all of the parameters for both color (see geometry::render::ColorRenderCamera) and depth (see geometry::render::DepthRenderCamera) cameras.

The various properties have restrictions on what they can be.

  • Values must be finite.
  • Some values must be positive (see notes on individual properties).
  • Ranges must be specified such that the "minimum" value is less than or equal to the "maximum" value. This includes the clipping range [clipping_near, clipping_far] and depth range [z_near, z_far].
  • The depth range must lie entirely within the clipping range.

The values are only checked when the configuration is operated on: during serialization, after deserialization, and when applying the configuration (see ApplyCameraConfig().)

#include <drake/systems/sensors/camera_config.h>

Classes

struct  FocalLength
 Specification of a camera's intrinsic focal properties as focal length (in pixels). More...
 
struct  FovDegrees
 Specification of focal length via fields of view (in degrees). More...
 

Public Member Functions

template<typename Archive >
void Serialize (Archive *a)
 Passes this object to an Archive. More...
 
std::pair< geometry::render::ColorRenderCamera, geometry::render::DepthRenderCameraMakeCameras () const
 Creates color and depth camera data from this configuration. More...
 
void ValidateOrThrow () const
 Throws if the values are inconsistent. More...
 

Public Attributes

Frustum-based camera properties
double clipping_near {0.01}
 The distance (in meters) from sensor origin to near clipping plane. More...
 
double clipping_far {500.0}
 The distance (in meters) from sensor origin to far clipping plane. More...
 
Depth camera range
double z_near {0.1}
 The distance (in meters) from sensor origin to closest measurable plane. More...
 
double z_far {5.0}
 The distance (in meters) from sensor origin to farthest measurable plane. More...
 
Camera extrinsics

The pose of the camera.

As documented in RgbdSensor, the camera has four associated frames: P, B, C, D. The frames of the parent (to which the camera body is rigidly affixed), the camera body, color sensor, and depth sensor, respectively. Typically, the body is posed w.r.t. the parent (X_PB) and the sensors are posed w.r.t. the body (X_BC and X_BD).

When unspecified, X_BD = X_BC = I by default.

schema::Transform X_PB
 The pose of the body camera relative to a parent frame P. More...
 
schema::Transform X_BC
 The pose of the color sensor relative to the camera body frame. More...
 
schema::Transform X_BD
 The pose of the depth sensor relative to the camera body frame. More...
 
Renderer properties

Every camera is supported by a geometry::render::RenderEngine instance.

These properties configure the render engine for this camera.

std::string renderer_name {"default"}
 The name of the geometry::render::RenderEngine that this camera uses. More...
 
std::variant< std::string, geometry::RenderEngineVtkParams, geometry::RenderEngineGlParams, geometry::RenderEngineGltfClientParamsrenderer_class {""}
 The choice of render engine implementation to use. More...
 
geometry::Rgba background {204 / 255.0, 229 / 255.0, 255 / 255.0, 1.0}
 The "background" color. More...
 
Publishing properties
std::string name {"preview_camera"}
 The camera name. More...
 
double fps {10.0}
 Publishing rate (in Hz) for both RGB and depth cameras (as requested). More...
 
double capture_offset {0.0}
 Phase offset (in seconds) for image capture, relative to the simulator's time zero. More...
 
double output_delay {0.0}
 Delay (in seconds) between when the scene graph geometry is "captured" and when the output image is published. More...
 
bool rgb {true}
 If true, RGB images will be produced and published via LCM. More...
 
bool depth {false}
 If true, depth images will be produced and published via LCM. More...
 
bool label {false}
 If true, label images will be produced and published via LCM. More...
 
bool show_rgb {false}
 Controls whether the rendered RGB and/or label images are displayed (in separate windows controlled by the thread in which the camera images are rendered). More...
 
bool do_compress {true}
 Controls whether the images are broadcast in a compressed format. More...
 
std::string lcm_bus {"default"}
 Which LCM URL to use. More...
 

Camera intrinsics

See CameraInfo.

int width {640}
 Image width (in pixels). More...
 
int height {480}
 Image height (in pixels). More...
 
std::variant< FocalLength, FovDegreesfocal {FovDegrees{.y = 45}}
 The focal properties of the camera. More...
 
std::optional< doublecenter_x {}
 The x-position of the principal point (in pixels). More...
 
std::optional< doublecenter_y {}
 The y-position of the principal point (in pixels). More...
 
double focal_x () const
 Returns the focal length (in pixels) in the x-direction. More...
 
double focal_y () const
 Returns the focal length (in pixels) in the y-direction. More...
 
Vector2< doubleprincipal_point () const
 Returns the position of the principal point. More...
 

Member Function Documentation

◆ focal_x()

double focal_x ( ) const

Returns the focal length (in pixels) in the x-direction.

◆ focal_y()

double focal_y ( ) const

Returns the focal length (in pixels) in the y-direction.

◆ MakeCameras()

Creates color and depth camera data from this configuration.

Exceptions
std::exceptionif configuration values do not satisfy the documented prerequisites.

◆ principal_point()

Vector2<double> principal_point ( ) const

Returns the position of the principal point.

This respects the semantics that undefined center_x and center_y place the principal point in the center of the image.

◆ Serialize()

void Serialize ( Archive *  a)

Passes this object to an Archive.

Refer to YAML Serialization for background.

◆ ValidateOrThrow()

void ValidateOrThrow ( ) const

Throws if the values are inconsistent.

Member Data Documentation

◆ background

geometry::Rgba background {204 / 255.0, 229 / 255.0, 255 / 255.0, 1.0}

The "background" color.

This is the color drawn where there are no objects visible. Its default value matches the default value for render::RenderEngineVtkParams::default_clear_color. See the documentation for geometry::Rgba::Serialize for how to define this value in YAML.

This value is used only if the render_class specifies either "RenderEngineVtk" or "RenderEngineGl" by name (RenderEngineGltfClient doesn't have a configurable background color.)

◆ capture_offset

double capture_offset {0.0}

Phase offset (in seconds) for image capture, relative to the simulator's time zero.

This can be useful to stagger multiple cameras. Refer to the RgbdSensorAsync class for a comprehensive description.

Precondition
capture_offset is non-negative and finite.

◆ center_x

std::optional<double> center_x {}

The x-position of the principal point (in pixels).

To query what the current value is, use principal_point().

Precondition
0 < center_x < width or is std::nullopt.

◆ center_y

std::optional<double> center_y {}

The y-position of the principal point (in pixels).

To query what the current value is, use principal_point().

Precondition
0 < center_y < height or is std::nullopt.

◆ clipping_far

double clipping_far {500.0}

The distance (in meters) from sensor origin to far clipping plane.

Precondition
clipping_far is a positive, finite number.

◆ clipping_near

double clipping_near {0.01}

The distance (in meters) from sensor origin to near clipping plane.

Precondition
clipping_near is a positive, finite number.

◆ depth

bool depth {false}

If true, depth images will be produced and published via LCM.

◆ do_compress

bool do_compress {true}

Controls whether the images are broadcast in a compressed format.

◆ focal

std::variant<FocalLength, FovDegrees> focal {FovDegrees{.y = 45}}

The focal properties of the camera.

It can be specified in one of two ways:

  • A FocalLength which specifies the focal lengths (in pixels) in the x- and y-directions.
  • An FovDegrees which defines focal length implicitly by deriving it from field of view measures (in degrees).

For both specifications, if only one value is given (in either direction), the focal length (as reported by focal_x() and focal_y()) is determined by that single value and is assumed to be symmetric for both directions.

Precondition
focal length(s) is a/are finite, positive number(s).

◆ fps

double fps {10.0}

Publishing rate (in Hz) for both RGB and depth cameras (as requested).

Precondition
fps is a positive, finite number.

◆ height

int height {480}

Image height (in pixels).

Precondition
height > 0.

◆ label

bool label {false}

If true, label images will be produced and published via LCM.

◆ lcm_bus

std::string lcm_bus {"default"}

Which LCM URL to use.

See also
drake::systems::lcm::LcmBuses

◆ name

std::string name {"preview_camera"}

The camera name.

This name is used as part of the corresponding RgbdSensor system's name and serves as a suffix of the LCM channel name.

Precondition
name is not empty.

◆ output_delay

double output_delay {0.0}

Delay (in seconds) between when the scene graph geometry is "captured" and when the output image is published.

Refer to the RgbdSensorAsync class for a comprehensive description.

Precondition
output_delay is non-negative and strictly less than 1/fps.

◆ renderer_class

The choice of render engine implementation to use.

It can be specified simply by providing a string containing the class name of the RenderEngine to use (i.e., "RenderEngineVtk", "RenderEngineGl", or "RenderEngineGltfClient"). Or, it can be specified by providing parameters for one of those engines: RenderEngineVtkParams, RenderEngineGlParams, or RenderEngineGltfClientParams.

If a string containing the render engine class name is provided, the engine instantiated will use the default parameters – equivalent to passing the set of default parameters.

It is possible for multiple cameras to reference the same renderer_name but configure the renderer differently. This would be a configuration error. The following rules will help prevent problematic configurations:

  • Multiple cameras can reference the same value for renderer_name.
  • If multiple cameras reference the same value for renderer_name, only the first can use the engine parameters to specify it. Attempting to do so with a later camera will produce an error.
    • The later cameras can use engine class name.
    • If a later camera names a different engine class, that will result in an error.

In YAML, it can be a bit trickier. Depending on how a collection of cameras is articulated, the concept of "first" may be unclear. In examples/hardware_sim/scenario.h the collection is a map. So, the camera configurations are not necessarily processed in the order they appear in the YAML file. Instead, the processing order depends on the mnemonic camera key. So, be aware, if you use a similar mapping, you may have to massage the key names to achieve the requisite processing order. Alternatively, a vector of CameraConfig in your own scenario file, would guarantee that processing order is the same as file order.

We intend to relax these restrictions in time, allowing equivalent, redundant specifications of a render engine (and throwing only on inconsistent specifications).

Passing the empty string is equivalent to saying, "I don't care". If a render engine with that name has already been configured, the camera will use it (regardless of type). If the name doesn't already exist, the default, slower, more portable, and more robust RenderEngineVtk will be instantiated. RenderEngineGl can be selected if you are on Ubuntu and need the improved performance (at the possible cost of lesser image fidelity). In YAML, omitting renderer_class from the camera specification is equivalent to "passing the empty string".

Configuring in YAML

It isn't always obvious what the proper spelling in YAML is. The following examples illustrate how the renderer_class field can be defined in YAML files.

  1. Use the RenderEngineVtk with all default parameters - providing the class name as a string.
    renderer_class: RenderEngineVtk
  2. Use the RenderEngineVtk with all default parameters - providing the engine parameters with default values.
    renderer_class: !RenderEngineVtkParams {}
  3. Use the RenderEngineVtk with a customized clear color (black).
    renderer_class: !RenderEngineVtkParams
    default_clear_color: [0, 0, 0]
  4. Use the RenderEngineGl with a customized clear color (black).
    renderer_class: !RenderEngineGlParams
    default_clear_color:
    rgba: [0, 0, 0, 1]
  5. Use the RenderEngineGltfClient with fully specified properties.
    renderer_class: !RenderEngineGltfClientParams
    base_url: http://10.10.10.1
    render_endpoint: server
    verbose: true
    cleanup: false
  6. Explicitly request Drake's default render engine.
    renderer_class: ""

Things to note:

  • When providing the parameters for the engine, the declaration must begin with ! to announce it as a type (examples 2, 3, and 4).
  • A defaulted set of parameters must have a trailing {} (example 2).
  • Two engine parameter sets may have the same semantic parameter but spell it differently (default_clear_color in examples 3 and 4).
Precondition
renderer_class is a string and either empty or one of "RenderEngineVtk", "RenderEngineGl", or "RenderEngineGltfClient", or, it is a parameter type of one of Drake's RenderEngine implementations.
See also
drake::geometry::SceneGraph::GetRendererTypeName().

◆ renderer_name

std::string renderer_name {"default"}

The name of the geometry::render::RenderEngine that this camera uses.

Generally, it is more efficient for multiple cameras to share a single render engine instance; they should, therefore, share a common renderer_name value.

Precondition
renderer_name is not empty.

◆ rgb

bool rgb {true}

If true, RGB images will be produced and published via LCM.

◆ show_rgb

bool show_rgb {false}

Controls whether the rendered RGB and/or label images are displayed (in separate windows controlled by the thread in which the camera images are rendered).

As both image types are rendered from ColorRenderCamera, it applies to both of them and depends on whether the RenderEngine instance supports it.

Note: This flag is intended for quick debug use during development instead of serving as an image viewer. Currently, there are known issues, e.g., flickering windows when multiple cameras share the same renderer or upside-down images if RenderEngineGl is set. See issue #18862 for the proposal to visualize images via Meldis.

◆ width

int width {640}

Image width (in pixels).

Precondition
width > 0.

◆ X_BC

The pose of the color sensor relative to the camera body frame.

Precondition
X_BC.base_frame is empty.

◆ X_BD

The pose of the depth sensor relative to the camera body frame.

Precondition
X_BD.base_frame is empty.

◆ X_PB

The pose of the body camera relative to a parent frame P.

If X_PB.base_frame is unspecified, then the world frame is assumed to be the parent frame.

Precondition
X_PB.base_frame is empty or refers to a valid, unique frame.

◆ z_far

double z_far {5.0}

The distance (in meters) from sensor origin to farthest measurable plane.

Precondition
z_near is a positive, finite number.

◆ z_near

double z_near {0.1}

The distance (in meters) from sensor origin to closest measurable plane.

Precondition
z_near is a positive, finite number.

The documentation for this struct was generated from the following file: