Drake
Image< kPixelType > Class Template Reference

Simple data format for Image. More...

#include <systems/sensors/image.h>

Collaboration diagram for Image< kPixelType >:
[legend]

Public Types

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 (int width, int height)
 Image size only constructor. More...
 
 Image (int width, int height, T initial_value)
 Image size and initial value constructor. More...
 
 Image ()=default
 Constructs a zero-sized image. 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...
 
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...
 

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.

Member Typedef Documentation

using T = typename Traits::ChannelType

The data type for a channel.

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 ( const Image< kPixelType > &  )
default
Image ( Image< kPixelType > &&  )
default
Image ( int  width,
int  height 
)
inline

Image size only constructor.

Specifies a width and height for the image. All the channel values in all the pixels are initialized with zero.

Parameters
widthSize of width for image which should be greater than zero
heightSize of height for image which should be greater than zero
Image ( int  width,
int  height,
T  initial_value 
)
inline

Image size and initial value constructor.

Specifies a width, height and an initial value for all the channels in all the pixels.

Parameters
widthSize of width for image which should be greater than zero.
heightSize of height for image which should be greater than zero.
initial_valueA value set to all the channels in all the pixels

Here is the call graph for this function:

Image ( )
default

Constructs a zero-sized image.

Here is the caller graph for this function:

Member Function Documentation

T* at ( int  x,
int  y 
)
inline

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];

Here is the caller graph for this function:

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

Const version of at() method.

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

int height ( ) const
inline

Returns the size of height for the image.

Here is the caller graph for this function:

Image& operator= ( Image< kPixelType > &&  )
default
Image& operator= ( const Image< kPixelType > &  )
default
void resize ( int  width,
int  height 
)
inline

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

The values for them should be greater than zero. (To resize to zero, assign a default- constructed Image into this; do not use this method.) All the values in the pixels become zero after resize.

Here is the call graph for this function:

int size ( ) const
inline

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

Here is the caller graph for this function:

int width ( ) const
inline

Returns the size of width for the image.

Here is the caller graph for this function:

Member Data Documentation

constexpr int kNumChannels = Traits::kNumChannels
static

The number of channels in a pixel.

constexpr PixelFormat kPixelFormat = Traits::kPixelFormat
static

The format for pixels.

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: