Drake
Drake C++ Documentation
RenderCameraCore Class Reference

Detailed Description

Collection of core parameters for modeling a pinhole-model camera in a RenderEngine.

These parameters are applicable to both depth and color/label renderings. Parameters specific to those output image types can be found below.

While these parameters are generally applicable to all RenderEngine implementations, this is not guaranteed to be true. For example, the clipping range property only applies to frustum-based RenderEngine implementations. I.e., it wouldn't apply to a ray-tracing based implementation.

#include <drake/geometry/render/render_camera.h>

Public Member Functions

 RenderCameraCore (std::string renderer_name, systems::sensors::CameraInfo intrinsics, ClippingRange clipping, math::RigidTransformd X_BS)
 Fully-specified constructor. More...
 
const std::string & renderer_name () const
 The name of the render engine this camera should be used with. More...
 
const systems::sensors::CameraInfointrinsics () const
 The camera's intrinsic properties (e.g., focal length, sensor size, etc.) See systems::sensors::CameraInfo for details. More...
 
const ClippingRangeclipping () const
 The near and far clipping planes for this camera. More...
 
const math::RigidTransformd & sensor_pose_in_camera_body () const
 The pose of the sensor frame (S) in the camera's body frame (B). More...
 
Eigen::Matrix4d CalcProjectionMatrix () const
 Expresses this camera's pinhole camera properties as the projective transform T_DC which transforms points in a camera's frame C to a 2D, normalized device frame D. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 RenderCameraCore (const RenderCameraCore &)=default
 
RenderCameraCoreoperator= (const RenderCameraCore &)=default
 
 RenderCameraCore (RenderCameraCore &&)=default
 
RenderCameraCoreoperator= (RenderCameraCore &&)=default
 

Constructor & Destructor Documentation

◆ RenderCameraCore() [1/3]

RenderCameraCore ( const RenderCameraCore )
default

◆ RenderCameraCore() [2/3]

◆ RenderCameraCore() [3/3]

RenderCameraCore ( std::string  renderer_name,
systems::sensors::CameraInfo  intrinsics,
ClippingRange  clipping,
math::RigidTransformd  X_BS 
)

Fully-specified constructor.

See the documentation on the member getter methods for documentation of parameters.

Member Function Documentation

◆ CalcProjectionMatrix()

Eigen::Matrix4d CalcProjectionMatrix ( ) const

Expresses this camera's pinhole camera properties as the projective transform T_DC which transforms points in a camera's frame C to a 2D, normalized device frame D.

The transform is represented by a 4x4 matrix (i.e., a classic OpenGl projection matrix).

◆ clipping()

const ClippingRange& clipping ( ) const

The near and far clipping planes for this camera.

This property is ignored by RenderEngine implementations that don't use a clipping frustum.

◆ intrinsics()

const systems::sensors::CameraInfo& intrinsics ( ) const

The camera's intrinsic properties (e.g., focal length, sensor size, etc.) See systems::sensors::CameraInfo for details.

◆ operator=() [1/2]

RenderCameraCore& operator= ( const RenderCameraCore )
default

◆ operator=() [2/2]

RenderCameraCore& operator= ( RenderCameraCore &&  )
default

◆ renderer_name()

const std::string& renderer_name ( ) const

The name of the render engine this camera should be used with.

◆ sensor_pose_in_camera_body()

const math::RigidTransformd& sensor_pose_in_camera_body ( ) const

The pose of the sensor frame (S) in the camera's body frame (B).

This is the "imager" referred to in systems::sensors::CameraInfo's documentation.


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