Drake
Drake C++ Documentation
Image< kPixelType > Class Template Reference

Detailed Description

template<PixelType kPixelType>
class drake::systems::sensors::Image< kPixelType >

Simple data format for Image.

For the complex calculation with the image, consider converting this to other libaries' Matrix data format, i.e., MatrixX in Eigen, Mat in OpenCV, and so on.

The origin of image coordinate system is on the left-upper corner.

Template Parameters
kPixelTypeThe pixel type enum that denotes the pixel format and the data type of a channel. TODO(zachfang): move most of the function definitions in this class to the .cc file.

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

Public Types

using NonTypeTemplateParameter = std::integral_constant< PixelType, kPixelType >
 This is used by generic helpers such as drake::Value to deduce a non-type template argument. More...
 
using Traits = ImageTraits< kPixelType >
 An alias for ImageTraits that contains the data type for a channel, the number of channels and the pixel format in it. More...
 
using T = typename Traits::ChannelType
 The data type for a channel. More...
 

Public Member Functions

 Image ()=default
 Constructs a zero-sized image. More...
 
 Image (int width, int height)
 Image size only constructor. More...
 
 Image (int width, int height, T initial_value)
 Image size and initial value constructor. More...
 
int width () const
 Returns the size of width for the image. More...
 
int height () const
 Returns the size of height for the image. More...
 
int size () const
 Returns the result of the number of pixels in a image by the number of channels in a pixel. More...
 
void resize (int width, int height)
 Changes the sizes of the width and height for the image. More...
 
Tat (int x, int y)
 Access to the pixel located at (x, y) in image coordinate system where x is the variable for horizontal direction and y is one for vertical direction. More...
 
const Tat (int x, int y) const
 Const version of at() method. More...
 
bool operator== (const Image &other) const
 Compares whether two images are exactly the same. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 Image (const Image &)=default
 
Imageoperator= (const Image &)=default
 
 Image (Image &&)=default
 
Imageoperator= (Image &&)=default
 

Static Public Attributes

static constexpr int kNumChannels = Traits::kNumChannels
 The number of channels in a pixel. More...
 
static constexpr int kPixelSize = kNumChannels * sizeof(T)
 The size of a pixel in bytes. More...
 
static constexpr PixelFormat kPixelFormat = Traits::kPixelFormat
 The format for pixels. More...
 

Member Typedef Documentation

◆ NonTypeTemplateParameter

using NonTypeTemplateParameter = std::integral_constant<PixelType, kPixelType>

This is used by generic helpers such as drake::Value to deduce a non-type template argument.

◆ T

using T = typename Traits::ChannelType

The data type for a channel.

◆ Traits

using Traits = ImageTraits<kPixelType>

An alias for ImageTraits that contains the data type for a channel, the number of channels and the pixel format in it.

Constructor & Destructor Documentation

◆ Image() [1/5]

Image ( const Image< kPixelType > &  )
default

◆ Image() [2/5]

Image ( Image< kPixelType > &&  )
default

◆ Image() [3/5]

Image ( )
default

Constructs a zero-sized image.

◆ Image() [4/5]

Image ( int  width,
int  height 
)

Image size only constructor.

Specifies a width and height for the image. The width and height can be either both zero or both strictly positive. All the channel values in all the pixels are initialized with zero.

◆ Image() [5/5]

Image ( int  width,
int  height,
T  initial_value 
)

Image size and initial value constructor.

Specifies a width, height and an initial value for all the channels in all the pixels. The width and height can be either both zero or both strictly positive.

Member Function Documentation

◆ at() [1/2]

T* at ( int  x,
int  y 
)

Access to the pixel located at (x, y) in image coordinate system where x is the variable for horizontal direction and y is one for vertical direction.

To access to the each channel value in the pixel (x, y), you can do:

ImageRgbaU8 image(640, 480, 255); uint8_t red = image.at(x, y)[0]; uint8_t green = image.at(x, y)[1]; uint8_t blue = image.at(x, y)[2]; uint8_t alpha = image.at(x, y)[3];

◆ at() [2/2]

const T* at ( int  x,
int  y 
) const

Const version of at() method.

See the document for the non-const version for the detail.

◆ height()

int height ( ) const

Returns the size of height for the image.

◆ operator=() [1/2]

Image& operator= ( const Image< kPixelType > &  )
default

◆ operator=() [2/2]

Image& operator= ( Image< kPixelType > &&  )
default

◆ operator==()

bool operator== ( const Image< kPixelType > &  other) const

Compares whether two images are exactly the same.

◆ resize()

void resize ( int  width,
int  height 
)

Changes the sizes of the width and height for the image.

The new width and height can be either both zero or both strictly positive. All the values in the pixels become zero after resize.

◆ size()

int size ( ) const

Returns the result of the number of pixels in a image by the number of channels in a pixel.

◆ width()

int width ( ) const

Returns the size of width for the image.

Member Data Documentation

◆ kNumChannels

constexpr int kNumChannels = Traits::kNumChannels
static

The number of channels in a pixel.

◆ kPixelFormat

constexpr PixelFormat kPixelFormat = Traits::kPixelFormat
static

The format for pixels.

◆ kPixelSize

constexpr int kPixelSize = kNumChannels * sizeof(T)
static

The size of a pixel in bytes.


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