Drake
Drake C++ Documentation
DepthRenderCamera Class Reference

Detailed Description

Collection of camera properties for cameras to be used with depth images.

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

Public Member Functions

 DepthRenderCamera (RenderCameraCore core, DepthRange depth_range)
 Fully-specified constructor. More...
 
const RenderCameraCorecore () const
 This camera's core render properties. More...
 
const DepthRangedepth_range () const
 The range of valid values for the depth camera. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 DepthRenderCamera (const DepthRenderCamera &)=default
 
DepthRenderCameraoperator= (const DepthRenderCamera &)=default
 
 DepthRenderCamera (DepthRenderCamera &&)=default
 
DepthRenderCameraoperator= (DepthRenderCamera &&)=default
 

Constructor & Destructor Documentation

◆ DepthRenderCamera() [1/3]

DepthRenderCamera ( const DepthRenderCamera )
default

◆ DepthRenderCamera() [2/3]

◆ DepthRenderCamera() [3/3]

DepthRenderCamera ( RenderCameraCore  core,
DepthRange  depth_range 
)

Fully-specified constructor.

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

Exceptions
std::exceptionif the depth_range is not fully contained within the clipping range.

Member Function Documentation

◆ core()

const RenderCameraCore& core ( ) const

This camera's core render properties.

◆ depth_range()

const DepthRange& depth_range ( ) const

The range of valid values for the depth camera.

◆ operator=() [1/2]

DepthRenderCamera& operator= ( const DepthRenderCamera )
default

◆ operator=() [2/2]

DepthRenderCamera& operator= ( DepthRenderCamera &&  )
default

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