RobWorkProject  23.9.11-
Classes | Public Types | Public Member Functions | Protected Attributes | List of all members
Image Class Reference

The image class is a simple wrapper around a char data array. This Image wrapper contain information of width, height and encoding. More...

#include <Image.hpp>

Classes

struct  Pixel4i
 

Public Types

enum  ColorCode {
  GRAY , RGB , RGBA , BGR ,
  BGRA , BayerBG , Luv , Lab ,
  HLS , User
}
 The color encodings that the image can use. This also defines the number channels that an image has. More...
 
enum  PixelDepth {
  Depth8U , Depth8S , Depth16U , Depth16S ,
  Depth32S , Depth32F
}
 The pixeldepth determines how many bits that are used per pixel per channel. More...
 
typedef rw::core::Ptr< ImagePtr
 smart pointer type to this class
 

Public Member Functions

 Image ()
 default constructor
 
 Image (unsigned int width, unsigned int height, ColorCode encoding, PixelDepth depth)
 constructor More...
 
 Image (char *imgData, unsigned int width, unsigned int height, ColorCode encoding, PixelDepth depth)
 constructor More...
 
virtual ~Image ()
 destructor
 
void resize (unsigned int width, unsigned int height)
 resizes the current image. More...
 
char * getImageData ()
 returns a char pointer to the image data More...
 
const char * getImageData () const
 returns a char pointer to the image data More...
 
void setImageData (char *data)
 sets the data array of this image. Make sure to change the height and width accordingly.
 
size_t getDataSize () const
 returns the size of the char data array More...
 
std::pair< unsigned int, unsigned int > getImageDimension ()
 returns the dimensions (width and height) of this image More...
 
unsigned int getWidth () const
 returns the width of this image More...
 
unsigned int getHeight () const
 returns the height of this image More...
 
ColorCode getColorEncoding () const
 returns color encoding/type of this image More...
 
unsigned int getBitsPerPixel () const
 returns the number of bits per pixel. This is the number of bits used per pixel per channel. More...
 
bool saveAsPGM (const std::string &fileName) const
 saves this image to a file in the PGM (grayscale) format More...
 
bool saveAsPGMAscii (const std::string &fileName) const
 saves this image to a file in the ascii PGM (grayscale) format More...
 
bool saveAsPPM (const std::string &fileName) const
 saves this image to a file in the PPM (color) format More...
 
unsigned int getWidthStep () const
 the size of an aligned image row in bytes. This may not be the same as the width if extra bytes are padded to each row for alignment purposes. More...
 
PixelDepth getPixelDepth () const
 bits per pixel encoded as a PixelDepth type. More...
 
unsigned int getNrOfChannels () const
 The number of channels that this image has. More...
 
Pixel4f getPixel (size_t x, size_t y) const
 generic but inefficient access to pixel information. The float value is between [0;1] which means non float images are scaled according to their pixel depth (bits per pixel). More...
 
Pixel4f getPixelf (size_t x, size_t y) const
 
void getPixel (size_t x, size_t y, Pixel4f &dst) const
 generic but inefficient access to pixel information. The float value is between [0;1] which means non float images are scaled according to their pixel depth (bits per pixel). More...
 
Pixel4i getPixeli (size_t x, size_t y) const
 generic access to pixel information, however user must take care of the pixel depth himself. If image is a Depth8U then the maximum value is 254. Also float images are scaled accordingly. More...
 
void getPixel (size_t x, size_t y, Pixel4i &dst) const
 generic access to pixel information, however user must take care of the pixel depth himself. If image is a Depth8U then the maximum value is 254. Also float images are scaled accordingly. More...
 
float getPixelValue (size_t x, size_t y, size_t channel) const
 generic but inefficient access to a specific channel of a pixel. More...
 
float getPixelValuef (size_t x, size_t y, size_t channel) const
 
int getPixelValuei (size_t x, size_t y, size_t channel) const
 
template<typename T >
void getPixelValue (size_t x, size_t y, size_t channel, T &dst) const
 
void setPixel (size_t x, size_t y, const Pixel4f &value)
 
void setPixel8U (const int x, const int y, uint8_t value)
 sets the gray tone in a 1-channel gray tone image with More...
 
void setPixel8U (const int x, const int y, uint8_t ch0, uint8_t ch1, uint8_t ch2)
 
void setPixel8U (const int x, const int y, uint8_t ch0, uint8_t ch1, uint8_t ch2, uint8_t ch3)
 
void setPixel8S (const int x, const int y, int8_t value)
 
void setPixel8S (const int x, const int y, int8_t ch0, int8_t ch1, int8_t ch2)
 
void setPixel8S (const int x, const int y, int8_t ch0, int8_t ch1, int8_t ch2, int8_t ch3)
 
void setPixel16U (const int x, const int y, uint16_t value)
 
void setPixel16U (const int x, const int y, uint16_t ch0, uint16_t ch1, uint16_t ch2)
 
void setPixel16U (const int x, const int y, uint16_t ch0, uint16_t ch1, uint16_t ch2, uint16_t ch3)
 
void setPixel16S (const int x, const int y, int16_t value)
 
void setPixel16S (const int x, const int y, int16_t ch0, int16_t ch1, int16_t ch2)
 
void setPixel16S (const int x, const int y, int16_t ch0, int16_t ch1, int16_t ch2, int16_t ch3)
 
void setPixel32S (const int x, const int y, int32_t value)
 
void setPixel32S (const int x, const int y, int32_t ch0, int32_t ch1, int32_t ch2)
 
void setPixel32S (const int x, const int y, int32_t ch0, int32_t ch1, int32_t ch2, int32_t ch3)
 
void setPixel32F (const int x, const int y, float value)
 
void setPixel32F (const int x, const int y, float ch0, float ch1, float ch2)
 
void setPixel32F (const int x, const int y, float ch0, float ch1, float ch2, float ch3)
 
template<PixelDepth DT>
void setPixel (const int x, const int y, int value)
 
template<PixelDepth DT>
void setPixel (const int x, const int y, float value)
 
template<PixelDepth DT>
void setPixel (const int x, const int y, const int ch0, const int ch1, const int ch2)
 
template<PixelDepth DT>
void setPixel (const int x, const int y, const int ch0, const int ch1, const int ch2, const int ch3)
 
Image::Ptr copyFlip (bool horizontal, bool vertical) const
 copies this image and flips it around horizontal or vertical axis or both. More...
 

Protected Attributes

size_t _arrSize
 width of a row in bytes, _width*_nrChannels*(bytesPerChannel)
 
char * _imageData
 Char array of image data.
 
size_t _stride
 
unsigned int _valueMask
 the stride of a pixel value
 
float _toFloat
 true if float representation is used
 
float _fromFloat
 

Detailed Description

The image class is a simple wrapper around a char data array. This Image wrapper contain information of width, height and encoding.

The image class is somewhat inspired by the IplImage of opencv.

The coordinate system has its origin located at the top-left position, where from X increases to the left and Y-increases downwards.

setting pixel values in an efficient manner has been enabled using some template joggling. It requires that the user know what type of image he/she is working with.

Member Enumeration Documentation

◆ ColorCode

enum ColorCode

The color encodings that the image can use. This also defines the number channels that an image has.

Enumerator
GRAY 

Grayscale image 1-channel.

RGB 

3-channel color image (Standard opengl)

RGBA 

4-channel color image with alpha channel

BGR 

3-channel color image (Standard OpenCV)

BGRA 

4-channel color image with alpha channel

◆ PixelDepth

enum PixelDepth

The pixeldepth determines how many bits that are used per pixel per channel.

Enumerator
Depth8U 

Depth8U.

Depth8S 

Depth8S.

Depth16U 

Depth16U.

Depth16S 

Depth16S.

Depth32S 

Depth32S.

Depth32F 

Depth32F.

Constructor & Destructor Documentation

◆ Image() [1/2]

Image ( unsigned int  width,
unsigned int  height,
ColorCode  encoding,
PixelDepth  depth 
)

constructor

Parameters
width[in] width of the image
height[in] height of the image
encoding[in] the colorCode of this Image
depth[in] the pixel depth in bits per channel

◆ Image() [2/2]

Image ( char *  imgData,
unsigned int  width,
unsigned int  height,
ColorCode  encoding,
PixelDepth  depth 
)

constructor

Parameters
imgData[in] char pointer that points to an array of chars with length width*height*(bitsPerPixel/8)
width[in] width of the image
height[in] height of the image
encoding[in] the colorCode of this Image
depth[in] the pixel depth in bits per channel

Member Function Documentation

◆ copyFlip()

Image::Ptr copyFlip ( bool  horizontal,
bool  vertical 
) const

copies this image and flips it around horizontal or vertical axis or both.

Returns
new image.

◆ getBitsPerPixel()

unsigned int getBitsPerPixel ( ) const

returns the number of bits per pixel. This is the number of bits used per pixel per channel.

Returns
number of bits per pixel

◆ getColorEncoding()

ColorCode getColorEncoding ( ) const
inline

returns color encoding/type of this image

Returns
ColorCode of this image

◆ getDataSize()

size_t getDataSize ( ) const

returns the size of the char data array

Returns
size of char data array

◆ getHeight()

unsigned int getHeight ( ) const

returns the height of this image

Returns
image height

◆ getImageData() [1/2]

char* getImageData ( )

returns a char pointer to the image data

Returns
char pointer to the image data

◆ getImageData() [2/2]

const char* getImageData ( ) const

returns a char pointer to the image data

Returns
const char pointer to the image data

◆ getImageDimension()

std::pair<unsigned int, unsigned int> getImageDimension ( )

returns the dimensions (width and height) of this image

Returns
a pair of integers where first is the width and second is the height

◆ getNrOfChannels()

unsigned int getNrOfChannels ( ) const
inline

The number of channels that this image has.

Returns
nr of channels

◆ getPixel() [1/3]

Pixel4f getPixel ( size_t  x,
size_t  y 
) const
inline

generic but inefficient access to pixel information. The float value is between [0;1] which means non float images are scaled according to their pixel depth (bits per pixel).

Parameters
x[in] x coordinate
y[in] y coordinate
Returns
up to 4 pixels (depends on nr of channels) in a float format

◆ getPixel() [2/3]

void getPixel ( size_t  x,
size_t  y,
Pixel4f dst 
) const

generic but inefficient access to pixel information. The float value is between [0;1] which means non float images are scaled according to their pixel depth (bits per pixel).

Parameters
x[in] x coordinate
y[in] y coordinate
dst[out] up to 4 pixels (depends on nr of channels) in a float format

◆ getPixel() [3/3]

void getPixel ( size_t  x,
size_t  y,
Pixel4i dst 
) const

generic access to pixel information, however user must take care of the pixel depth himself. If image is a Depth8U then the maximum value is 254. Also float images are scaled accordingly.

Parameters
x[in] x coordinate
y[in] y coordinate
dst[out] up to 4 pixels (depends on nr of channels) in a float format

◆ getPixelDepth()

PixelDepth getPixelDepth ( ) const
inline

bits per pixel encoded as a PixelDepth type.

Returns
the pixel depth

◆ getPixeli()

Pixel4i getPixeli ( size_t  x,
size_t  y 
) const

generic access to pixel information, however user must take care of the pixel depth himself. If image is a Depth8U then the maximum value is 254. Also float images are scaled accordingly.

Parameters
x[in] x coordinate
y[in] y coordinate
Returns
up to 4 pixels (depends on nr of channels) as ints

◆ getPixelValue()

float getPixelValue ( size_t  x,
size_t  y,
size_t  channel 
) const
inline

generic but inefficient access to a specific channel of a pixel.

Parameters
x[in]
y[in]
channeldocumentation missing !
Returns
the pixel value.

◆ getWidth()

unsigned int getWidth ( ) const

returns the width of this image

Returns
image width

◆ getWidthStep()

unsigned int getWidthStep ( ) const
inline

the size of an aligned image row in bytes. This may not be the same as the width if extra bytes are padded to each row for alignment purposes.

Returns
size of aligned image row

◆ resize()

void resize ( unsigned int  width,
unsigned int  height 
)

resizes the current image.

Parameters
width[in] width in pixels
height[in] height in pixels

◆ saveAsPGM()

bool saveAsPGM ( const std::string &  fileName) const

saves this image to a file in the PGM (grayscale) format

Parameters
fileName[in] the name of the file that is to be created
Returns
true if save was succesfull, false otherwise

◆ saveAsPGMAscii()

bool saveAsPGMAscii ( const std::string &  fileName) const

saves this image to a file in the ascii PGM (grayscale) format

Parameters
fileName[in] the name of the file that is to be created
Returns
true if save was succesfull, false otherwise

◆ saveAsPPM()

bool saveAsPPM ( const std::string &  fileName) const

saves this image to a file in the PPM (color) format

Parameters
fileName[in] the name of the file that is to be created
Returns
true if save was succesfull, false otherwise

◆ setPixel8U()

void setPixel8U ( const int  x,
const int  y,
uint8_t  value 
)
inline

sets the gray tone in a 1-channel gray tone image with

Parameters
x
y
value

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