$search
Templated image class. More...
#include <tpimage.h>
Public Member Functions | |
T * | GetData () const |
Get image data position. | |
int | GetHeight () const |
Get image height. | |
int | GetWidth () const |
Get image width. | |
Image (int w, int h, T *ptr=NULL) | |
Constructor. | |
bool | Load (const char *filename) |
Load grey-level image from PGM file. | |
bool | LoadRGB (const char *filename) |
Load RGB image (three values per pixel) from PPM file. | |
void | operator= (Image< T > &src) |
Copy image data. | |
T * | operator[] (int i) |
Get pointer to pixel row i. | |
void | SetData (T *ptr) |
Set image data position. | |
void | SetDataAlign (const sensor_msgs::Image &img_msg, int w, int h, bool withColor=true) |
Set image data position and ensure correct alignment. | |
void | SetDataAlign (T *ptr, int w, int h) |
Set image data position and ensure correct alignment. | |
void | SetSize (int w, int h) |
Set new image size. | |
void | Store (const char *filename, bool norm=false, bool ascii=false) const |
Store grey-level image as PGM file. | |
void | StoreRGB (const char *filename) const |
Store RGB image (three values per pixel) as PPM file. | |
void | StoreYUV (const char *filename) const |
Convert from UYVY (two values per pixel) to RGB and store as PPM file. | |
~Image () | |
Private Attributes | |
int | height |
T * | image |
T * | img |
bool | localalloc |
int | width |
Templated image class.
Definition at line 53 of file tpimage.h.
Constructor.
w | image width | |
h | image height | |
ptr | image data pointer (if NULL, allocated internally) |
Definition at line 36 of file tpimage.cpp.
T* Image< T >::GetData | ( | ) | const [inline] |
int Image< T >::GetHeight | ( | ) | const [inline] |
int Image< T >::GetWidth | ( | ) | const [inline] |
bool Image< T >::Load | ( | const char * | filename | ) | [inline] |
Load grey-level image from PGM file.
filename | image file name |
Definition at line 152 of file tpimage.cpp.
bool Image< T >::LoadRGB | ( | const char * | filename | ) | [inline] |
Load RGB image (three values per pixel) from PPM file.
filename | image file name |
Definition at line 212 of file tpimage.cpp.
Copy image data.
Definition at line 409 of file tpimage.cpp.
T* Image< T >::operator[] | ( | int | i | ) | [inline] |
void Image< T >::SetData | ( | T * | ptr | ) | [inline] |
void Image< T >::SetDataAlign | ( | const sensor_msgs::Image< T > & | img_msg, | |
int | w, | |||
int | h, | |||
bool | withColor = true | |||
) | [inline] |
Set image data position and ensure correct alignment.
image | ROS image sensor message | |
w | image width | |
h | image height |
Definition at line 102 of file tpimage.cpp.
void Image< T >::SetDataAlign | ( | T * | ptr, | |
int | w, | |||
int | h | |||
) | [inline] |
Set image data position and ensure correct alignment.
ptr | image data pointer | |
w | image width | |
h | image height |
Definition at line 79 of file tpimage.cpp.
void Image< T >::SetSize | ( | int | w, | |
int | h | |||
) | [inline] |
Set new image size.
w | image width | |
h | image height |
Definition at line 58 of file tpimage.cpp.
void Image< T >::Store | ( | const char * | filename, | |
bool | norm = false , |
|||
bool | ascii = false | |||
) | const [inline] |
Store grey-level image as PGM file.
filename | image file name | |
norm | whether to normalize image before storage | |
ascii | whether to store in ASCII or binary format |
Definition at line 281 of file tpimage.cpp.
void Image< T >::StoreRGB | ( | const char * | filename | ) | const [inline] |
Store RGB image (three values per pixel) as PPM file.
filename | image file name |
Definition at line 348 of file tpimage.cpp.
void Image< T >::StoreYUV | ( | const char * | filename | ) | const [inline] |
Convert from UYVY (two values per pixel) to RGB and store as PPM file.
filename | image file name |
Definition at line 373 of file tpimage.cpp.
bool Image< T >::localalloc [private] |