AURobotServers  4
Public Member Functions | Static Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
UImage Class Reference

#include <uimage.h>

Inheritance diagram for UImage:
Inheritance graph

Public Member Functions

void clear (UPixel rgb)
 
void clear (void)
 
void clear (int v)
 
bool colorSaturate (double gain)
 
bool colourSaturate (double gain)
 
bool copy (UImage *source)
 
bool copyAndScale (UImage *source, double factor)
 
bool copyJustImage (UImage *source)
 
bool copyMeta (UImage *source, bool andSize)
 
bool copyScaleDown (UImage *source, int factor)
 
bool copyToMaxRes (UImage *source)
 
CvArr * cvArr ()
 
void edgeSobel (UImage *destination, bool absoluteValue=true, int reducFactor=1)
 
bool fromMat (char *colorFormatString=NULL)
 
bool fromMat (cv::Mat src, char *colorFormatString=NULL)
 
unsigned int getBufferSize ()
 Get number of bytes in image buffer. This is the total size of the allocated image buffer. This may be larger than the the number of bytes actually used by the image, and allows thus change in image size or format without allocating new buffer space. More...
 
int getChannels ()
 
char * getCharRef (unsigned int line, unsigned int column)
 
int getColorType ()
 
const char * getColorTypeString ()
 
UImage ** getConvertBuffer ()
 
UPixelgetData ()
 
unsigned int getDataSize ()
 
int getDepth ()
 
unsigned int getHeight ()
 
UTime getImageTime ()
 
int * getIntRef (unsigned int line, unsigned int column)
 
IplImage * getIplImage ()
 
UPixelgetLine (unsigned int line)
 
bool GetNewNonCameraImage ()
 
UPixel getPix (unsigned int line, unsigned int column)
 
UPixel getPix (unsigned int line, unsigned int column, int inColFormat)
 
int getPixInt (unsigned int line, unsigned int column)
 
UPixelgetPixRef (unsigned int line, unsigned int column)
 
bool getQuadPix (unsigned int line, unsigned int column, unsigned char *I11, unsigned char *I12, unsigned char *I21, unsigned char *I22, unsigned char *U, unsigned char *V)
 
unsigned char * getUCharRef (unsigned int line, unsigned int column)
 
unsigned char * getUline (unsigned int line)
 
UTime getUpdatedTime ()
 
unsigned char * getVline (unsigned int line)
 
unsigned int getWidth ()
 
unsigned char * getYline (unsigned int line)
 
void gridLine (float Pos, char axis, float minH, float maxH, float minW, float maxW, char sw= 'y', int Color=1)
 
void gridLines (float major, float minor, char axis, float minH, float maxH, float minW, float maxW, char sw)
 
unsigned int height ()
 
void hLine (unsigned int line, unsigned int c1, unsigned int c2, int p1, int p2, int p3)
 
unsigned int imgBytes ()
 
virtual void imgUpdated ()
 
bool initImage (const unsigned int iHeight, const unsigned int iWidth, char *data, const unsigned int bufferSize, const int channels=3, const int depth=8)
 
bool inRange (int line, int column)
 
bool invertY ()
 
bool isBayer ()
 
bool isBGR ()
 
bool isBW ()
 
bool isBW16s ()
 
bool isBW16u ()
 
bool isRGB ()
 
bool isRGBA ()
 
bool isTooBig (const unsigned int w, const unsigned int h)
 
bool isValid ()
 
bool isYUV ()
 
bool isYUV420 ()
 
bool isYUV422 ()
 
void lineInGrid (UPosition pos1, UPosition pos2, float minH, float maxH, float minW, float maxW, char sw, UPixel *rgb, UMatrix4 *mA=NULL, int lineWidth=1)
 
bool loadBMP (const char filename[])
 
bool loadBMP (const char path[], const char basename[], const int num, const char nameAdd[])
 
bool loadPNG (const char *filename)
 
unsigned int maxBytes ()
 
unsigned int maxPixels ()
 
bool median (UImage *dimg, unsigned int row1, unsigned int col1, unsigned int row2, unsigned int col2, unsigned int fW, unsigned int fH)
 
void moveBW16ToRGB (UImage *dest)
 
int packZLIB (char *buffer, int bufferSize)
 
void paintGridAligned (const int r0, const int c0, const double pixPerM, const int strongTicEvery)
 
int pixCmp (UPixel *p1, UPixel *p2)
 
UPixel pixRGB (unsigned char r, unsigned char g, unsigned char b)
 
UPixelpixSort (UPixel ***ps, int pixCnt)
 
UPixel pixYUV (unsigned char y, unsigned char u, unsigned char v)
 
bool resize (const unsigned int iHeight, const unsigned int iWidth, const int channels=3, const int depth=8)
 
bool resizeBuffer (const unsigned int iHeight, const unsigned int iWidth, const int channels, const int depth)
 
bool saveBMP (const char filename[])
 
bool saveBMP (const char path[], const char basename[], const int num, const char nameAdd[])
 
bool saveMeta (const char *name, const char *type, const char *path)
 
bool savePNG (const char *filename)
 
bool saveTxt (const char *filename)
 
int setColorType (const char *)
 
bool setColorType (int colorFormat)
 
bool setMaxSize43 ()
 
void setName (const char *imageName)
 
void setNameAndExt (const char *basename, const char *ext=NULL)
 
void setPix (unsigned int line, unsigned int column, UPixel pix)
 
void setPixChar (unsigned int line, unsigned int column, char pix)
 
void setPixel (int x1, int y1, UPixel rgb, UImage *image=NULL, int procent=0)
 
void setPixInt (unsigned int line, unsigned int column, int pix)
 
void setPixUChar (unsigned int line, unsigned int column, unsigned char pix)
 
bool setQuadPix (unsigned int line, unsigned int column, unsigned char I11, unsigned char I12, unsigned char I21, unsigned char I22, unsigned char U, unsigned char V)
 
void setROI (int x, int y, int w, int h)
 
bool setSize (const unsigned int iHeight, const unsigned int iWidth, const int channels, const int depth, const char *colorType=NULL)
 
bool setSizeOnly (const unsigned int iHeight, const unsigned int iWidth)
 
void shiftCols (int cols, int byteFill=-1)
 
void shiftRows (int rows, int byteFill=-1)
 
UPixel sobel (UPixel *p1, UPixel *p2, UPixel *p3)
 
UPixel sobel (UPixel *p1, UPixel *p2, UPixel *p3, UPixel *pixRef, int reducFactor)
 
bool toBGR (UImage *dest=NULL)
 
bool toBW (UImage *dest=NULL)
 
bool toCromaBGR (UImage *dest=NULL)
 
bool toHalf ()
 
bool toMat ()
 
void tone (UPixel *rgb, int procent)
 
void tone (UPixel rgb, int procent)
 
bool toRaibow (UImage *gray)
 
bool toRaibowInv (UImage *gray)
 
bool toRGB (UImage *dest=NULL)
 
bool toRGBA (UImage *dest=NULL)
 
bool toYUV (UImage *dest=NULL)
 
 UImage ()
 
bool unpackZLIB (int rows, int cols, const char *colFormat, char *buffer, int bufferCnt)
 
void updated ()
 
void vLine (unsigned int col, unsigned int r1, unsigned int r2, int p1, int p2, int p3)
 
unsigned int width ()
 
bool yuv422toBGR (uint8_t *source, int h, int w)
 
bool yuv422toBGRhalf (uint8_t *source, int h, int w)
 
bool yuv422toBW (uint8_t *source, int h, int w)
 
bool yuv422toRGB (uint8_t *source, int h, int w)
 
bool yuv422toRGBhalf (uint8_t *source, int h, int w)
 
bool yuv422toYUV (uint8_t *source, int h, int w)
 
bool yuv422toYUVhalf (uint8_t *source, int h, int w)
 
virtual ~UImage ()
 
- Public Member Functions inherited from ULock
bool lock ()
 
void lockInit ()
 
void post ()
 
bool tryLock ()
 
bool tryWait ()
 
 ULock ()
 
void unlock ()
 
bool wait ()
 
 ~ULock ()
 

Static Public Member Functions

static int toColFormatInt (const char *col)
 

Public Attributes

void * cam
 
int camDevice
 
unsigned int hdrSet
 
unsigned long imageNumber
 
UTime imgTime
 
cv::Mat mat
 
char name [MAX_IMG_NAME_SIZE]
 
UPosition pos
 
bool radialErrorRemoved
 
float readDelay
 
URotation rot
 
char saveType [MAX_EXT_SIZE]
 
int source
 
unsigned int used
 
bool valid
 

Protected Member Functions

bool moveBGGRTo (int toColFormat, UImage *dest)
 
bool moveBGGRtoBGR (UImage *dest)
 
bool moveBGGRtoBW (UImage *dest)
 
void moveBGGRToHalfBGR ()
 
bool moveBGGRtoRGB (UImage *dest)
 
void moveBWToHalf ()
 
void movePixToHalf ()
 
bool moveYUV420To (int toColFormat, UImage *dest)
 
void moveYUV420ToHalf ()
 
void moveYUV420ToHalf (UImage *dst)
 

Protected Attributes

unsigned int bufferBytes
 
int colFormat
 
IplImage img
 
UTime imgUpdateTime
 
unsigned char * pu
 
unsigned char * pv
 
unsigned char * py
 

Private Attributes

UImageconvertBuffer
 

Detailed Description

Class to hold a virtual an image with all the functionality of an image.
Should only be used as UImage640 or similar

Constructor & Destructor Documentation

UImage::UImage ( )
UImage::~UImage ( )
virtual

Destructor

References convertBuffer, and img.

Member Function Documentation

void UImage::clear ( UPixel  rgb)
void UImage::clear ( void  )

Clears the image to white, and makes the image valid

References getData(), and imgBytes().

Referenced by colorSaturate().

void UImage::clear ( int  v)

Clears all bytes in image to this value.

References getData(), imgBytes(), and valid.

bool UImage::colorSaturate ( double  gain)
inline
bool UImage::colourSaturate ( double  gain)

Increase colour diversity by applying this gain to the colour channels, ie multiply U=(U-128)*gain and V(V-128)*gain. Saturation limits to 255 and 0. gain may have one decimal, as the value is calculated as integer - the used operation is U = ((U-128) * int(gain*8)) >> 3)

References colFormat, getData(), getUCharRef(), getUline(), height(), isBGR(), isBW(), isRGB(), isYUV(), maxi(), mini(), UPixel::p1, UPixel::p2, UPixel::p3, PIX_PLANES_BGR, PIX_PLANES_RGB, PIX_PLANES_YUV, PIX_PLANES_YUV420, PIX_PLANES_YUV422, roundi(), UPixel::setRGBto(), UPixel::setYUVto(), UPixel::u, UPixel::v, width(), and UPixel::y.

Referenced by colorSaturate(), UFunctionImage::handleImageGetCommand(), and updated().

bool UImage::copy ( UImage source)
bool UImage::copyAndScale ( UImage source,
double  factor 
)

Copy source image to this image and scale this image with factor. The scaling uses nearest neighbour method (no interpolation)

Parameters
sourceis the image to copy
factoris the scale factor - 0.5 reduces to half size, 3 expands each axis by a factor 3.
Returns
true if scaling succeded.

References copyMeta(), cvArr(), getChannels(), getDepth(), height(), isYUV420(), moveYUV420ToHalf(), resize(), roundi(), and width().

Referenced by colorSaturate(), and UFunctionImgPool::handleImageGetCommand().

bool UImage::copyJustImage ( UImage source)

Copy image rgb data, width and height, leaving other data unchanged

References getChannels(), getData(), getDepth(), height(), imgBytes(), maxBytes(), resize(), setSize(), used, and width().

Referenced by colorSaturate(), copy(), UFunctionImgPool::handleImageGetCommand(), toRGB(), toRGBA(), and toYUV().

bool UImage::copyMeta ( UImage source,
bool  andSize 
)

Clears or sets all UImage propreties to a default value Copy just image meta data, that is name, time, position and color format, position etc., but not the bitmap itself. if 'andSize', then the image size and color format is changed to that of the source image. A full copy is implemented as a copyMeta() followed by a copyJustImage().

References cam, camDevice, colFormat, getBufferSize(), getChannels(), getDataSize(), getDepth(), hdrSet, height(), imageNumber, imgTime, name, pos, radialErrorRemoved, readDelay, resize(), rot, saveType, setColorType(), used, and width().

Referenced by UFuncCog::calculateCOG(), UFuncCropRow::CannyEdge(), colorSaturate(), copy(), copyAndScale(), copyToMaxRes(), UFuncStraightLine::crop(), UFuncImSeg::doLBPhistogramMatch(), edgeSobel(), UFuncBallKL::filterMask(), UFuncPiPi::filterMask(), UFuncCropRow::filterMask(), UFuncBall::filterMask(), UFuncBall_improved::filterMask(), UFuncLinefinder::filterMask(), UImAna::findContourPolyCroma(), UImageAna::findContourPolyCroma(), UImagePoly::findContourPolyCroma(), UImageAna::findRoad(), UImageAna::findRoadCroma(), UImAna::findRoadPoly(), UImageAna::findRoadPoly(), UImagePoly::findRoadPoly(), UFuncCropRow::handleCommand(), UFuncStraightLine::handleCommand(), UFunctionImgPool::handleImageGetCommand(), UFuncImSeg::makeLBPimage(), UImagePoly::makeSimilarImage2(), UImagePoly::makeSimilarImage3(), UCalibrate::MarkCornerDetections4(), UFuncBallKL::maskColors(), UFuncPiPi::maskColors(), UFuncBall::maskColors(), UFuncBall_improved::maskColors(), UFuncCropRow::maskColors(), UFuncLinefinder::maskColors(), UFuncImSeg::meanShiftSegment(), moveBGGRtoBGR(), moveBGGRtoBW(), moveBGGRtoRGB(), moveBW16ToRGB(), moveYUV420To(), moveYUV420ToHalf(), UFuncFz::paintColoredImage(), UFuncKinect::processDepthImages(), UFuncStereo::processImages(), UCamRad::removeRadialError(), savePNG(), testMatrixVecBig(), testOpticalFlow(), testOpticalFlowHarris(), toBGR(), toBW(), toCromaBGR(), toRGB(), toRGBA(), and toYUV().

bool UImage::copyScaleDown ( UImage source,
int  factor 
)

Make a copy of source image, but scanle size down by the integer factor provided. The scale down uses center pixel in new image. Reurns true if possible.

References cam, colFormat, getChannels(), getDepth(), getLine(), height(), imageNumber, imgTime, name, pos, radialErrorRemoved, rot, saveType, setSize(), used, valid, and width().

Referenced by colorSaturate(), harris2(), and testEigenvector().

bool UImage::copyToMaxRes ( UImage source)

Resample source image to destination image, so that it fills to max size. The copy is not optimized, and there is no anti-aliasing, and at decreasing size the nearest pixel is used only.
Some image parameters are copied as well, i.e.: time, name, number, intensity, isRGB, cam. Returns false if source data is not valid

References copyMeta(), cvArr(), height(), setSizeOnly(), and width().

Referenced by colorSaturate(), UClientFuncImgGui::gotNewImage(), testImageHandling(), and testMatrixVecBig().

CvArr* UImage::cvArr ( )
inline

Get array structure recognized by opencv

References img.

Referenced by UResObj3d::addGroundObjects(), UFuncBallKL::calculateBallPosition(), UFuncPiPi::calculateBallPosition(), UFuncBall::calculateBallPosition(), UFuncBall_improved::calculateBallPosition(), UFuncCog::calculateCOG(), UFuncCropRow::CannyEdge(), copyAndScale(), copyToMaxRes(), UResObj3d::do3dVoxels(), UFuncFz::doClassify(), UCalibrationComponents::doFindCodeCellIntensity(), UResObj3d::doGndPlaneMask(), UFuncImSeg::doGrayLevelCooccurenceMatrix(), UClientFuncLaserGui::doImage(), UCalibrationComponents::doOrderHits4(), UImgPolyProj::doPolygonMap(), UImgProj::doPolygonMap(), UClientFuncLaserGui::doRepaint(), UFuncBallKL::filterMask(), UFuncPiPi::filterMask(), UFuncCropRow::filterMask(), UFuncBall::filterMask(), UFuncBall_improved::filterMask(), UFuncLinefinder::filterMask(), UFuncBallKL::findBallCandidates(), UFuncPiPi::findBallCandidates(), UFuncBall::findBallCandidates(), UFuncBall_improved::findBallCandidates(), UCalibrate::findBarcodeChartPosition(), UImAna::findContour(), UImageAna::findContour(), UResObj3d::findContour(), UImAna::findContourPolyCroma(), UImageAna::findContourPolyCroma(), UImagePoly::findContourPolyCroma(), UFuncLinefinder::findEnd(), UCalibrate::findGmk(), UFuncCropRow::findPlants(), UResObj3d::findPolygonLargest(), UResObj3d::findPolygons(), UImageAna::findRoad(), UImageAna::findRoadCroma(), UImageAna::findRoadFill(), UImAna::findRoadPoly(), UImageAna::findRoadPoly(), UImagePoly::findRoadPoly(), getCharRef(), getIntRef(), getPixRef(), getUCharRef(), UClientFuncImgGui::gotNewImage(), gridLine(), UFuncCropRow::handleCommand(), harris3(), UFuncLinefinder::houghTest(), lineInGrid(), UResObj3d::makeGroundPlaneProfileImage(), UProbGrid::makeProbGrid(), UImagePoly::makeSimilarImage2(), UImagePoly::makeSimilarImage3(), UFuncLinefinder::maskColors(), UFuncImSeg::meanShiftSegment(), moveBGGRtoBGR(), moveBGGRtoRGB(), UNavPaint::paint(), UNavPaint::paintCams(), UCalibrationComponents::PaintChartInImage(), UClientFuncImgGui::paintClustEllipse(), UFuncFz::paintClustEllipse(), UNavPaint::paintCross(), UClientFuncLaserGui::paintCross(), UGroundPatches::paintDebugGrid(), UGroundPatches::paintDebugValue(), UClientFuncLaserGui::paintEkfData(), UNavPaint::paintFeatures(), UNavPaint::paintFreePoly(), UClientFuncLaserGui::paintFreePoly(), UNavPaint::paintGmks(), UResObj3d::paintGndPlane(), UProbGrid::paintGrid(), UImgPolyProj::paintGrid(), UImgProj::paintGrid(), paintGridAligned(), UCalibrationComponents::PaintGridInImage(), UNavPaint::paintHistScan(), UClientFuncLaserGui::paintHistScan(), UCalibrationComponents::PaintHitsInImage(), UClientFuncLaserGui::paintLineSegments(), UNavPaint::paintManData(), UCalibrationComponent::PaintNeighbors(), UNavPaint::paintObstGrp(), UClientFuncLaserGui::paintObstGrp(), UClientFuncLaserGui::paintOdoData(), UNavPaint::paintOdoDataText(), UNavPaint::paintOdoGrid(), UClientFuncLaserGui::paintOdoGrid(), UClientFuncLaserGui::paintPathData(), UNavPaint::paintPis(), UClientFuncLaserGui::paintPis(), UClientFuncLaserGui::paintPlannerData(), UResObj3d::paintPolygonInImage(), UNavPaint::paintPolyItems(), UNavPaint::paintPose(), UClientFuncLaserGui::paintPose(), UNavPaint::paintPoseHistLine(), UClientFuncLaserGui::paintPostHistLine(), UNavPaint::paintRangeRings(), UClientFuncLaserGui::paintRangeRings(), UNavPaint::paintRoadLine(), UProbPoly::paintRobot(), UImgPolyProj::paintRobot(), UImgProj::paintRobot(), UNavPaint::paintRobotField(), UNavPaint::paintRobotGuidebot(), UNavPaint::paintRobotHako(), UNavPaint::paintRobotIrobot(), UClientFuncLaserGui::paintRobotMmr(), UNavPaint::paintRobotMmr(), UImgProj::paintRobotPath(), UImgPolyProj::paintRobotPath(), UClientFuncLaserGui::paintRobotSmr(), UNavPaint::paintRobotSmr(), UNavPaint::paintScanNewest(), UNavPaint::paintScanStatData(), UClientFuncLaserGui::paintScanStatData(), UImgProj::paintText(), UImgPolyProj::paintText(), UNavPaint::paintVarDataText(), UGrid3D::paintVoxels(), UClientFuncLaserGui::paintWpc(), UClientFuncLaserGui::paintWpListData(), pixYUV(), UFuncStereo::processImages(), UCamRad::removeRadialError(), UClientFuncLaserGui::saveImage(), UClientFuncImgGui::saveImage(), UClientFuncImgGui::showFocusNumber(), UHighGuiWindowHandle::showImage(), UClientFuncImgGui::showLine(), UClientFuncImgGui::showUVImage(), UResDisp::showUVImage(), testImageHandling(), testMatrixVecBig(), testOpenCv(), testOpticalFlow(), testOpticalFlowHarris(), testSobel(), toBGR(), toBW(), toRGB(), and toRGBA().

void UImage::edgeSobel ( UImage destination,
bool  absoluteValue = true,
int  reducFactor = 1 
)

Edge filter the image to the destination image. if 'absoluteValue' the the result is the absolute value of the sum of found edges. Else the found signed sum is added to the source image - as a contour enhancement. The reducFactor is used to divide the found value, so a factor 4 gives an average value of the 4 edge filtrers.

References copyMeta(), getLine(), height(), maxi(), mini(), UPixel::set(), sobel(), and width().

Referenced by UImageAna::findRoadFill(), getBufferSize(), and testSobel().

bool UImage::fromMat ( char *  colorFormatString = NULL)

copy a cv:Mat image to the (old ) UImage format This will make a copy of the cvMat data area to to UImage buffer. Only images with 1 and 4 channels can be converted (e.g. RGBA and 8bit gray images)

Returns
true if conversion is sucessfull

References getData(), getDataSize(), mat, setSize(), and updated().

Referenced by getConvertBuffer(), and UFuncImSeg::makeLBPimage().

bool UImage::fromMat ( cv::Mat  src,
char *  colorFormatString = NULL 
)

copy a cv:Mat image to the (old ) UImage format from this source - the comor frmat can be set too. This will make a copy of the cvMat data area to to UImage buffer. Only images with 1 and 4 channels can be converted (e.g. RGBA and 8bit gray images)

Parameters
srcis the image source in cv::Mat format
colorFormatString(default is NULL) can be RGB, BGR, RGBA, YUV or GRAY ...
Returns
true if conversion is sucessfull

References getData(), getDataSize(), setSize(), and updated().

unsigned int UImage::getBufferSize ( )
inline

Get number of bytes in image buffer. This is the total size of the allocated image buffer. This may be larger than the the number of bytes actually used by the image, and allows thus change in image size or format without allocating new buffer space.

Returns
number of bytes in reserver buffer (unsigned integer)

References edgeSobel(), getQuadPix(), getUline(), getVline(), getYline(), hLine(), imgUpdated(), maxBytes(), median(), pixCmp(), pixSort(), setQuadPix(), shiftCols(), shiftRows(), sobel(), and vLine().

Referenced by copyMeta(), UCamDevGigE::frameToImage(), UCamDevGuppy::~UCamDevGuppy(), and UCamDevIeee1394::~UCamDevIeee1394().

int UImage::getChannels ( )
inline
char* UImage::getCharRef ( unsigned int  line,
unsigned int  column 
)
inline

Get a pointer to a pixel, - for use with 8-bit BW images

Parameters
lineis row number starting at 0 counting down in image (less than height())
columnis coloumn starting at 0 counting positive right (less than width())
Returns
pointer to this pixel.

References cvArr().

Referenced by UFuncImSeg::cooccurrence(), UFuncStraightLine::crop(), UFuncImSeg::doLBPhistogramMatch(), UFuncImSeg::doPatchHistogram(), UFuncImSeg::doPatchHistogramLBP8(), UFuncStraightLine::findLines(), UFuncStraightLine::GLR(), UFuncStraightLine::mean(), moveYUV420ToHalf(), UFuncStereo::processImages(), setPixChar(), and UFuncStraightLine::threshold().

int UImage::getColorType ( )
inline
const char * UImage::getColorTypeString ( )
UImage** UImage::getConvertBuffer ( )
inline

Get address of convert buffer pointer - for fixed allocated convert buffer space. The buffer is an integrated part of the UImage structure, and needs to be allocated, when first used. It will be deallocated when image is deallocated (deleted).

Returns
adress of convert buffer pointer inside image structure.

References convertBuffer, fromMat(), and toMat().

Referenced by UImgPush::fillShowBuffer(), UFuncRectify::handleCommand(), UHighGuiWindowHandle::showImage(), UQtgui::updateImg(), and MainWindow::updateImg().

UPixel* UImage::getData ( )
inline
unsigned int UImage::getDataSize ( )
inline
int UImage::getDepth ( )
inline
unsigned int UImage::getHeight ( )
inline
UTime UImage::getImageTime ( )
inline

Get image timestamp time (when the image was taken). The image update time is set when image was first captured.

References imgTime, moveBW16ToRGB(), paintGridAligned(), toHalf(), toRaibow(), and toRaibowInv().

Referenced by UFunctionCamGmk::handleGmkGetCommand(), UFuncStereo::processImages(), UFuncPiCam::run(), UFuncStraightLine::toRobot(), UFuncStraightLine::toWorld(), and UFuncKinect::updateCloud().

int* UImage::getIntRef ( unsigned int  line,
unsigned int  column 
)
inline

Get a pointer to a pixel, - for use with 32-bit color images

Parameters
lineis row number starting at 0 counting down in image (less than height())
columnis coloumn starting at 0 counting positive right (less than width())
Returns
pointer to this pixel.

References cvArr(), getPix(), and getPixInt().

Referenced by setPixInt().

IplImage* UImage::getIplImage ( )
inline

get pointer to openCV image header. This is used in connection with image functions other than the simple byte conversions.

References img.

Referenced by UFuncStraightLine::handleCommand(), UFuncImSeg::meanShiftSegment(), UFuncTOF::processChannel8(), UFuncStereo::processImages(), UFuncTOF::processImages(), and UFuncPTgrey::Receiver().

UPixel* UImage::getLine ( unsigned int  line)
inline

Get a pointer to an image line of UPixels

Parameters
lineis row number starting at 0 counting down in image (less than height())
Returns
pointer to first pixel in line

References getPixRef().

Referenced by UFuncFocus::calculateFocusValue(), UGroundPatch::colorAnalysis(), copyScaleDown(), UImAna::distFilt(), UImageAna::distFilt(), UImagePoly::distFilt(), UImAna::distFiltH(), UImageAna::distFiltH(), UImagePoly::distFiltH(), UClientFuncImgGui::doFuzzyClassify(), edgeSobel(), UImAna::findContourPoly(), UImageAna::findContourPoly(), UImAna::findContourPolyCroma(), UImageAna::findContourPolyCroma(), UImagePoly::findContourPolyCroma(), UImageAna::findRoad(), UImageAna::findRoadCroma(), UImageAna::findRoadFill(), UImAna::findRoadPoly(), UImageAna::findRoadPoly(), UImagePoly::findRoadPoly(), UImAna::getAvgVar(), UImageAna::getAvgVar(), UImagePoly::getAvgVar(), UImagePoly::getAvgVar2(), UFuncKinect::GetXYZCoordinates(), harris(), harris2(), harris3(), hLine(), UFuncFz::initializeClassesFromLine(), loadBMP(), loadPNG(), UFuncImSeg::makeLBPimage(), UFuncKinect::makeObj3Dcloud(), UProbGrid::makeProbGrid(), UImagePoly::makeSimilarImage2(), UImagePoly::makeSimilarImage3(), UFuncBallKL::maskColors(), UFuncPiPi::maskColors(), UFuncBall::maskColors(), UFuncBall_improved::maskColors(), UFuncCropRow::maskColors(), UFuncLinefinder::maskColors(), UFuncImSeg::meanShiftSegment(), median(), moveBW16ToRGB(), moveYUV420To(), UClientFuncImgGui::paintClustPixels(), UFuncFz::paintClustPixels(), UFuncFz::paintColoredImage(), saveBMP(), UProbGrid::saveMatlab(), savePNG(), UFunctionImgBase::sendImage(), shiftCols(), shiftRows(), UClientFuncImgGui::showFocusNumber(), UClientFuncImgGui::showUVImage(), UResDisp::showUVImage(), testCameraHDR(), testEigenvector(), testMatrixVecBig(), tone(), vLine(), yuv422toBGR(), yuv422toBGRhalf(), yuv422toBW(), yuv422toRGB(), yuv422toRGBhalf(), yuv422toYUV(), and yuv422toYUVhalf().

bool UImage::GetNewNonCameraImage ( )

Set image as valid image without any camera and with max size. Primarily used for planar view images, where no camera projection is needed.

References cam, UPosition::clear(), URotation::clear(), imageNumber, imgTime, maxBytes(), name, UTime::Now(), pos, rot, saveType, setMaxSize43(), used, and valid.

Referenced by setName().

UPixel UImage::getPix ( unsigned int  line,
unsigned int  column 
)
UPixel UImage::getPix ( unsigned int  line,
unsigned int  column,
int  inColFormat 
)

Get a UPixel at this position. Line count positive down and column counts positiove right. Returns pixel in desired color format (YUV420 returns in YUV) and BW returns in YUV too.

References UPixel::asBGR(), UPixel::asRGB(), UPixel::asYUV(), colFormat, getPix(), PIX_PLANES_BGR, PIX_PLANES_BW, PIX_PLANES_RGB, PIX_PLANES_YUV, PIX_PLANES_YUV420, and PIX_PLANES_YUV422.

int UImage::getPixInt ( unsigned int  line,
unsigned int  column 
)

Get pixel as integer. The pixel is coded as 0xRRGGBB 3x 8 bit if in RGB format or in general 0xP1P2P3 for the 3 pixel planes in 3x8 bit color.

Parameters
lineis the image line - zero is left, positive right.
columnis the image column - zero is top line, positive down.
Returns
pixel packed into integer.

References colFormat, getData(), getPixRef(), getUline(), getVline(), getYline(), UPixel::p1, UPixel::p2, UPixel::p3, PIX_PLANES_BW, PIX_PLANES_YUV420, PIX_PLANES_YUV422, and width().

Referenced by getIntRef().

UPixel* UImage::getPixRef ( unsigned int  line,
unsigned int  column 
)
inline
bool UImage::getQuadPix ( unsigned int  line,
unsigned int  column,
unsigned char *  I11,
unsigned char *  I12,
unsigned char *  I21,
unsigned char *  I22,
unsigned char *  U,
unsigned char *  V 
)

Get the 4 intensity values and the related color information. The line and column is for the full image resolution, but is truncated so that the LSB is not used - i.e. getQuadPix(5,5, ...) gets same values as getQuadPix(4,4, ...) Returns true if in range - otherwise no data. NB! works correct if format is YUV420 only!

References colFormat, getUline(), getVline(), getYline(), height(), PIX_PLANES_YUV420, and width().

Referenced by getBufferSize().

unsigned char* UImage::getUCharRef ( unsigned int  line,
unsigned int  column 
)
inline

Get a pointer to a pixel, - for use with unsigned 8-bit BW images

Parameters
lineis row number starting at 0 counting down in image (less than height())
columnis coloumn starting at 0 counting positive right (less than width())
Returns
pointer to this pixel.

References cvArr().

Referenced by UFuncKinect::callGotNewDataWithObject(), colourSaturate(), UFunctionImgPool::handleImageGetCommand(), UFuncCropRow::maskColors(), UFuncImSeg::meanShiftSegment(), UFuncPTgrey::Receiver(), savePNG(), saveTxt(), setPixUChar(), toBW(), toHalf(), toRaibow(), toRaibowInv(), toYUV(), and UGrid3D::voxelSegmentation().

unsigned char * UImage::getUline ( unsigned int  line)

Get line array for U-intensity at half resolution. line has range 0 to (height / 2 - 1). Returns NULL if out of range. Returns pointer to array of bytes lpU[line * width / 2]. NB! works correct if format is YUV420 only!

References height(), pu, and width().

Referenced by UFuncCog::calculateCOG(), colourSaturate(), getBufferSize(), getPix(), getPixInt(), getQuadPix(), moveYUV420ToHalf(), UCamRad::removeRadialError(), UFunctionImgBase::sendImage(), and setQuadPix().

UTime UImage::getUpdatedTime ( )
inline

Get image update time. The image update time is set by a call to 'imgUpdate' and is always in current processor time - replay or not.

References imgUpdateTime.

Referenced by UHighGuiWindowHandle::isTime().

unsigned char * UImage::getVline ( unsigned int  line)

Get line array for V-intensity at half resolution. line has range 0 to (height / 2 - 1). Returns NULL if out of range. Returns pointer to array of bytes lpV[line * width / 2]. NB! works correct if format is YUV420 only!

References height(), pv, and width().

Referenced by UFuncCog::calculateCOG(), getBufferSize(), getPix(), getPixInt(), getQuadPix(), moveYUV420ToHalf(), UCamRad::removeRadialError(), UFunctionImgBase::sendImage(), and setQuadPix().

unsigned int UImage::getWidth ( )
inline
unsigned char * UImage::getYline ( unsigned int  line)

Get line array for intensity (full resolution) Returns NULL if out of range. Returns pointer to array intensity bytes lpY[width]. NB! works correct if format is YUV420 only!

References height(), img, and py.

Referenced by UFuncCog::calculateCOG(), UFuncFocus::calculateFocusValue(), UImgStat::evaluateStatistics(), getBufferSize(), getPix(), getPixInt(), getQuadPix(), moveYUV420ToHalf(), UCamPwc::readFramesThread(), UCamDevice::readFramesThread(), UCamRad::removeRadialError(), and setQuadPix().

void UImage::gridLine ( float  Pos,
char  axis,
float  minH,
float  maxH,
float  minW,
float  maxW,
char  sw = 'y',
int  Color = 1 
)

Paints a line across the image at position pos for axis (in x,y,z) given the limits min and max for both axis and axis specifier sw colour is 1:Minor,2:Major,3:Zero, 4,4++ dotted in major colour if sw = 'z' then axis='x' means width (right positive) and axis='y' means height (up positive)

References cvArr(), height(), UPixel::p1, UPixel::p2, UPixel::p3, roundi(), and width().

Referenced by gridLines(), and inRange().

void UImage::gridLines ( float  major,
float  minor,
char  axis,
float  minH,
float  maxH,
float  minW,
float  maxW,
char  sw 
)

Paints a series of grid lines along one coordinate (axis) axis specified as above. 'major' is major line distance, 'minor' is minor line distance. sw: // y => x-z plot => axis: x or z - z as width z => y-x plot => axis: y or x - x as width x => y-z plot => axis: y or z - z as width

References absf(), and gridLine().

Referenced by inRange().

unsigned int UImage::height ( )
inline

Get image height in pixels.

References img.

Referenced by UFuncCog::calculateCOG(), UFuncFocus::calculateFocusValue(), UFuncKinect::callGotNewDataWithObject(), clear(), colourSaturate(), UFuncImSeg::cooccurrence(), copyAndScale(), copyJustImage(), copyMeta(), copyScaleDown(), copyToMaxRes(), UImAna::distFiltH(), UImageAna::distFiltH(), UImagePoly::distFiltH(), UFuncFz::doClassify(), UCalibrationComponents::doFindCodeCellIntensity(), UClientFuncImgGui::doFuzzyClassify(), UClientFuncLaserGui::doImage(), UFuncImSeg::doLBPhistogramMatch(), UFuncImSeg::doPatchHistogram(), UFuncImSeg::doPatchHistogramLBP8(), UImgPolyProj::doPolygonMap(), UImgProj::doPolygonMap(), UImgPolyProj::doProject(), UImgProj::doProject(), UImgPolyProj::doProjectPolygonToMapPix(), UImgProj::doProjectPolygonToMapPix(), UClientFuncLaserGui::doRepaint(), edgeSobel(), UCalibrationComponents::EnumerateCalibrationDetections(), UCalibrationComponents::EnumerateCalibrationDetections4(), UFuncBallKL::findBall(), UFuncBall::findBall(), UFuncBall_improved::findBall(), UCalibrationComponents::findClosestNeighbors(), UImAna::findContour(), UImageAna::findContour(), UImAna::findContourPoly(), UImageAna::findContourPoly(), UImAna::findContourPolyCroma(), UImageAna::findContourPolyCroma(), UImagePoly::findContourPolyCroma(), UCalibrate::findGmk(), UImageAna::findRoad(), UImageAna::findRoadCroma(), UImageAna::findRoadFill(), UImAna::findRoadPoly(), UImageAna::findRoadPoly(), UImagePoly::findRoadPoly(), UFuncImSeg::findSegments(), UResCamIfImg::getImageBuffer(), getQuadPix(), UImAna::getRoadProbability(), UImageAna::getRoadProbability(), UImagePoly::getRoadProbability(), getUline(), getVline(), getYline(), UClientFuncImage::gotNewImage(), gridLine(), UFuncCropRow::handleCommand(), UFunctionImgPool::handleImageListCommand(), UFuncImgPoly::handleImgPolyCommand(), UFunctionCamPath::handlePathGetCommand(), harris(), harris2(), harris3(), hLine(), UImageAna::imageContour2(), UImagePoly::imageContour2(), UImAna::imageContourMaha(), UImageAna::imageContourMaha(), UImagePoly::imageContourMaha(), UImAna::imageUsable(), UImageAna::imageUsable(), UImagePoly::imageUsable(), imgBytes(), UImgPush::imgUpdated(), UFuncFz::initializeClassesFromLine(), invertY(), lineInGrid(), loadBMP(), UFuncFz::loadNewImage(), UFuncImSeg::makeLBPimage(), UFuncKinect::makeObj3Dcloud(), UProbGrid::makeProbGrid(), UProbGrid::makeProbGrid2(), UImagePoly::makeSimilarImage2(), UImagePoly::makeSimilarImage3(), UCalibrate::MarkCornerDetections4(), UFuncImSeg::meanShiftSegment(), median(), UNavPaint::mousePan(), UNavPaint::mouseScale(), moveBGGRtoBGR(), moveBGGRtoBW(), moveBGGRToHalfBGR(), moveBGGRtoRGB(), moveBW16ToRGB(), moveBWToHalf(), movePixToHalf(), moveYUV420To(), moveYUV420ToHalf(), UNavPaint::paint(), UClientFuncImgGui::paintClustPixels(), UFuncFz::paintClustPixels(), UFuncFz::paintColoredImage(), UGroundPatches::paintDebugGrid(), UClientFuncLaserGui::paintEkfData(), UNavPaint::paintFeatures(), UClientFuncLaserGui::paintFreePoly(), UResObj3d::paintGndPlane(), UProbGrid::paintGrid(), UImgPolyProj::paintGrid(), UImgProj::paintGrid(), UClientFuncLaserGui::paintHistScan(), UClientFuncLaserGui::paintLineSegments(), UClientFuncLaserGui::paintObstGrp(), UClientFuncLaserGui::paintOdoData(), UNavPaint::paintOdoDataText(), UClientFuncLaserGui::paintOdoDest(), UClientFuncLaserGui::paintOdoGrid(), UClientFuncLaserGui::paintPathData(), UClientFuncLaserGui::paintPis(), UClientFuncLaserGui::paintPostHistLine(), UClientFuncLaserGui::paintRangeRings(), UImAna::paintRoadImage(), UImageAna::paintRoadImage(), UImagePoly::paintRoadImage(), UImgProj::paintRobot(), UImgPolyProj::paintRobot(), UClientFuncLaserGui::paintRobotMmr(), UImgProj::paintRobotPath(), UImgPolyProj::paintRobotPath(), UClientFuncLaserGui::paintRobotSmr(), UNavPaint::paintScanStatData(), UClientFuncLaserGui::paintScanStatData(), UClientFuncLaserGui::paintWpc(), UClientFuncLaserGui::paintWpListData(), pixYUV(), UFuncStereo::processImages(), UImgPush::run(), UFuncV4lGst::run(), UImgPush::runShow(), saveBMP(), UProbGrid::saveMatlab(), savePNG(), saveTxt(), UFunctionImgBase::sendImage(), setQuadPix(), shiftCols(), shiftRows(), UClientFuncImgGui::showFocusNumber(), UHighGuiWindowHandle::showImage(), UClientFuncImgGui::showLine(), UClientFuncImgGui::showUVImage(), UResDisp::showUVImage(), testEigenvector(), testMatrixVecBig(), testOpenCv(), testZlib(), toBGR(), toBW(), toCromaBGR(), toHalf(), toMat(), tone(), toRaibow(), toRaibowInv(), toRGB(), toRGBA(), toYUV(), unpackZLIB(), UQtgui::updateImg(), MainWindow::updateImg(), UFuncV4lGst::useBuffer(), and vLine().

void UImage::hLine ( unsigned int  line,
unsigned int  c1,
unsigned int  c2,
int  p1,
int  p2,
int  p3 
)

Paint horizontal line in one or more of the image planes from column 'c1' to column 'c2'. paint with value p1, p2, p3 in the 3 planes, if a plane is -1 (negative) then plane is not changed.

References getLine(), height(), maxi(), mini(), UPixel::p1, UPixel::p2, UPixel::p3, and width().

Referenced by getBufferSize().

unsigned int UImage::imgBytes ( )
inline
void UImage::imgUpdated ( )
virtual
bool UImage::initImage ( const unsigned int  iHeight,
const unsigned int  iWidth,
char *  data,
const unsigned int  bufferSize,
const int  channels = 3,
const int  depth = 8 
)

Initialize image data area. This buffer area must be at least iHeight * iWidth * channels, as pixels are always in unsigned bye format.

References bufferBytes, img, setSize(), and valid.

Referenced by UImage160::UImage160(), UImage320::UImage320(), UImage640::UImage640(), and UImage800::UImage800().

bool UImage::inRange ( int  line,
int  column 
)
inline
bool UImage::invertY ( )

Invert intensity for image, by inverting the Y channal. If The image is RGB then it is converted before the operation and back after the operation. returns 0;

References getData(), height(), isBW(), width(), and UPixel::y.

Referenced by colorSaturate().

bool UImage::isBayer ( )
inline
bool UImage::isBGR ( )
inline
bool UImage::isBW ( )
inline
bool UImage::isBW16s ( )
inline

Is 16 bit signed BW image

References colFormat, and PIX_PLANES_BW16S.

Referenced by savePNG(), testUImage(), and toBW().

bool UImage::isBW16u ( )
inline

Is 16 bit signed BW image

References colFormat, and PIX_PLANES_BW16U.

Referenced by toBW().

bool UImage::isRGB ( )
inline
bool UImage::isRGBA ( )
inline

Is color format RGB

References colFormat, and PIX_PLANES_RGBA.

Referenced by toRGBA().

bool UImage::isTooBig ( const unsigned int  w,
const unsigned int  h 
)
inline

Test to see if the image can hold an image of this size

References colFormat, loadBMP(), loadPNG(), maxPixels(), name, packZLIB(), rows, saveBMP(), saveMeta(), savePNG(), saveTxt(), and unpackZLIB().

bool UImage::isValid ( )
inline

Is image valid (configured)

References valid.

Referenced by UImAna::imageUsable(), UImageAna::imageUsable(), and UImagePoly::imageUsable().

bool UImage::isYUV ( )
inline
bool UImage::isYUV420 ( )
inline
bool UImage::isYUV422 ( )
inline

Is YUV 422 planar format

References colFormat, and PIX_PLANES_YUV422.

Referenced by UImgPush::fillShowBuffer().

void UImage::lineInGrid ( UPosition  pos1,
UPosition  pos2,
float  minH,
float  maxH,
float  minW,
float  maxW,
char  sw,
UPixel rgb,
UMatrix4 mA = NULL,
int  lineWidth = 1 
)

Paint a free line in image from position 1 to position 2 in specified color, width and perspective as indicated

References cvArr(), height(), UPixel::p1, UPixel::p2, UPixel::p3, roundi(), UPosition::transfer(), width(), UPosition::x, UPosition::y, and UPosition::z.

Referenced by inRange().

bool UImage::loadBMP ( const char  filename[])
bool UImage::loadBMP ( const char  path[],
const char  basename[],
const int  num,
const char  nameAdd[] 
)

Load an image in Windows BMP format with more separate name components. There is always added an ".bmp" extension. e.g. saveBMP("/home/chr", "img0045", 7, "Gaus3x3"); is equvivalent with saveBMP("/home/chr/img0045-07Gaus3x3.bmp"); The image name is set to the same name excluding the path. If the integer part 'num' is -1, then the "-07" part of the name is omitted

References loadBMP(), MAX_IMG_NAME_SIZE, and name.

bool UImage::loadPNG ( const char *  filename)

Load an RGB image in png format (no larger than buffer allows). Filename is assumed to be fully qualified.

References getLine(), maxBytes(), setSize(), and width().

Referenced by UFuncKinect::decodeReplayLine(), UCamPool::decodeReplayLine(), UFunctionImgPool::handleImageSetCommand(), isTooBig(), UResDisp::loadImgToPool(), and testPng().

unsigned int UImage::maxBytes ( )
inline
unsigned int UImage::maxPixels ( )
inline

Get buffer size in bytes

References bufferBytes, and img.

Referenced by clear(), isTooBig(), and setMaxSize43().

bool UImage::median ( UImage dimg,
unsigned int  row1,
unsigned int  col1,
unsigned int  row2,
unsigned int  col2,
unsigned int  fW,
unsigned int  fH 
)

Do median filter for a part of an image. The part from (row1, col1) to (row2,col2) is filtered - row1,col1 must be top-left corner. at edges the edge pixel is reused as needed. The row and column row2 and col2 is not inclusive in the filtered area. Returns true if destination image is valid and mask size is within handled size (fH <= 11 and (fH * fW) < 200.

References getLine(), height(), maxi(), mini(), pixSort(), and width().

Referenced by getBufferSize().

bool UImage::moveBGGRTo ( int  toColFormat,
UImage dest 
)
protected

Convert image format RGGB Bayer (raw from ieee1394 cam) to one of the other formats

Parameters
toColFormatis the new color format.
destis the destination image, may be same image (and is, if dest== NULL).
Returns
true if OK

References moveBGGRtoBGR(), moveBGGRtoBW(), moveBGGRtoRGB(), PIX_PLANES_BGR, PIX_PLANES_BW, PIX_PLANES_RGB, PIX_PLANES_YUV, and toYUV().

Referenced by toBGR(), toBW(), toRGB(), toRGBA(), and toYUV().

bool UImage::moveBGGRtoBGR ( UImage dest)
protected

Move BGGR to BGR (24 bit) - using openCV.

Parameters
destis the destination image, may be same image (and is, if dest== NULL).
Returns
true if image buffer has space for BGR image -as this is 3 times the size of the original image.

References convertBuffer, copy(), copyMeta(), cvArr(), getColorType(), height(), PIX_PLANES_BGGR, PIX_PLANES_GBRG, PIX_PLANES_GRBG, PIX_PLANES_RGGB, setSize(), UImage(), and width().

Referenced by moveBGGRTo().

bool UImage::moveBGGRtoBW ( UImage dest)
protected

Move BGGR to BW - using the green values only, and narest neighbour.

Parameters
destis the destination image, may be same image (and is, if dest== NULL).
Returns
true

References absi(), bool2str(), copyMeta(), getData(), getHeight(), getWidth(), height(), img, PIX_PLANES_BW, setColorType(), setSize(), UIMAGE_MAX_WIDTH, and width().

Referenced by moveBGGRTo().

void UImage::moveBGGRToHalfBGR ( )
protected
bool UImage::moveBGGRtoRGB ( UImage dest)
protected

Move BGGR to RGB (24 bit) using openCV.

Parameters
destis the destination image, may be same image (and is, if dest== NULL).
Returns
true if image buffer has space for BGR image -as this is 3 times the size of the original image.

References convertBuffer, copy(), copyMeta(), cvArr(), getColorType(), height(), PIX_PLANES_BGGR, PIX_PLANES_GBRG, PIX_PLANES_GRBG, PIX_PLANES_RGGB, setSize(), UImage(), and width().

Referenced by moveBGGRTo().

void UImage::moveBW16ToRGB ( UImage dest)

save a BW16S format as RGB - no data loss

References a, copyMeta(), getData(), getLine(), height(), PIX_PLANES_RGB, UPixel::set(), setColorType(), and width().

Referenced by getImageTime(), toBGR(), toRGB(), and toRGBA().

void UImage::moveBWToHalf ( )
protected

Downsample BW image to half size

References height(), img, setSizeOnly(), and width().

Referenced by toHalf().

void UImage::movePixToHalf ( )
protected

Downsample any UPixel based image (RGB, BGR, YUV) to half size

References getData(), height(), UPixel::p1, UPixel::p2, UPixel::p3, setSizeOnly(), and width().

Referenced by toHalf().

bool UImage::moveYUV420To ( int  toColFormat,
UImage dest 
)
protected

Convert image format YUV420 (raw from webcam) to one of the other formats

Parameters
toColFormatis the new color format.
destis the destination image, may be same image (and is, if dest== NULL).
Returns
true if OK

References colFormat, copyMeta(), getData(), getDataSize(), getLine(), height(), PIX_PLANES_BGR, PIX_PLANES_BW, PIX_PLANES_RGB, PIX_PLANES_YUV, setColorType(), setSize(), UPixel::setYUVto(), and width().

Referenced by toBGR(), toBW(), toCromaBGR(), toRGB(), toRGBA(), and toYUV().

void UImage::moveYUV420ToHalf ( )
protected

Downsample TYV420 coded image to half size in YUV format

References getData(), getUline(), getVline(), getYline(), height(), img, UPixel::p1, UPixel::p2, UPixel::p3, pu, pv, setSize(), UIMAGE_MAX_WIDTH, and width().

Referenced by copyAndScale(), and toHalf().

void UImage::moveYUV420ToHalf ( UImage dst)
protected

Downsample YUV420 to half size but stil in YUV420 format

Parameters
dstis the destination image

References copyMeta(), getCharRef(), getUline(), getVline(), height(), setSize(), and width().

int UImage::packZLIB ( char *  buffer,
int  bufferSize 
)

Pack image data using Z-lib. Returns the number of bytes used in the buffer. Returns -1 packing failed. Will fail if ZLIB is not available

References getData(), imgBytes(), and packZlib().

Referenced by isTooBig(), and testZlib().

void UImage::paintGridAligned ( const int  r0,
const int  c0,
const double  pixPerM,
const int  strongTicEvery 
)

Paint simple grid aligned with x and y axis. The origin is at (r0,c0) row and column number, a tick every meter and stronger ticks regularly. Origin lines are in blue, simple ticks week gray and strong tics a bit darker. Designed for white background.

Parameters
r0,c0the grid origin in pixels
pixPerMeternumber of pixels per meter (one tick per meter)
strongTicEverystrong tick interval (e.g. 10 for every 10 meter)

References cvArr(), getHeight(), getWidth(), and roundi().

Referenced by UResObj3d::addGroundObjects(), getImageTime(), UResObj3d::paintGndPlane(), UGrid3D::paintVoxels(), and UResDisp::showUVImage().

int UImage::pixCmp ( UPixel p1,
UPixel p2 
)

Compare pixels for intensity (r+g+b). Returns positive if p1 > p2, and 0 if equal, and negative if p2 > p1.

References a, UPixel::p1, UPixel::p2, and UPixel::p3.

Referenced by getBufferSize(), and pixSort().

UPixel UImage::pixRGB ( unsigned char  r,
unsigned char  g,
unsigned char  b 
)

Get a pixel value in right color format from RGB source

References colFormat, PIX_PLANES_BGR, PIX_PLANES_BW, PIX_PLANES_RGB, PIX_PLANES_YUV, UPixel::RGBtoYUV(), UPixel::set(), and UPixel::y.

Referenced by setName(), testCameraHDR(), and testMatrixVecBig().

UPixel * UImage::pixSort ( UPixel ***  ps,
int  pixCnt 
)

Order this number of pixels after intensity in all channels, Uses pixCmp(...) to when sorting pixels. Returns the center element. NB! no range checks

References pixCmp().

Referenced by getBufferSize(), and median().

UPixel UImage::pixYUV ( unsigned char  y,
unsigned char  u,
unsigned char  v 
)
bool UImage::resize ( const unsigned int  iHeight,
const unsigned int  iWidth,
const int  channels = 3,
const int  depth = 8 
)

Resize image - and rearrange image buffer as needed

Returns
true if possible

References bufferBytes, img, resizeBuffer(), setSize(), and valid.

Referenced by copyAndScale(), copyJustImage(), copyMeta(), UFuncV4lGst::run(), testUImage(), and UImgPush::UImgPush().

bool UImage::resizeBuffer ( const unsigned int  iHeight,
const unsigned int  iWidth,
const int  channels,
const int  depth 
)

Resize image buffer (if needed). Allocates more memory image buffer (realloc) if new size is larger than current buffer. if image is smaller than buffer no action is taken.

Parameters
iHeightis the new image height.
iWidthis the new image width.
channelsis the number of colour channels (1=BW, 3 or 4 if colour)
depthis number of bits per channel - usually 8 (is truncated down to bytes, i.e. 8 and 16 is allowed only).
Returns
true if buffer can hold specified image.

References bufferBytes, and img.

Referenced by resize(), setSize(), and setSizeOnly().

bool UImage::saveBMP ( const char  filename[])
bool UImage::saveBMP ( const char  path[],
const char  basename[],
const int  num,
const char  nameAdd[] 
)

Saves the image in Windows BMP format with more separate name components. There is always added an ".bmp" extension. e.g. saveBMP("/home/chr", "img0045", 7, "Gaus3x3"); is equvivalent with saveBMP("/home/chr/img0045-07Gaus3x3.bmp"); The image name is set to the same name excluding the path. If the integer part 'num' is -1, then the "-07" part of the name is omitted

References add, MAX_IMG_NAME_SIZE, name, and saveBMP().

bool UImage::saveMeta ( const char *  name,
const char *  type,
const char *  path 
)

Save image meta data to file. Returns true if saved.

Referenced by isTooBig(), and testImageLoadSave().

bool UImage::savePNG ( const char *  filename)
bool UImage::saveTxt ( const char *  filename)

Save image as space separated integer values line by line. Filename is assumed to be fully qualified.

References getDepth(), getUCharRef(), height(), and width().

Referenced by UFunctionImgPool::handleImageGetCommand(), and isTooBig().

int UImage::setColorType ( const char *  col)
bool UImage::setColorType ( int  colorFormat)

Set image color format to one of PIX_PLANES_BW , PIX_PLANES_RGB, PIX_PLANES_BGR, PIX_PLANES_YUV, PIX_PLANES_YUV420, PIX_PLANES_YUV422, PIX_PLANES_BW16S. (16 bit signed integer per pixel), PIX_PLANES_BGGR (Bayer coded 1 plane image) PIX_PLANES_RGGB (Bayer coded 1 plane image) PIX_PLANES_BGRA (32 bit interger per pixel (1 plane image in openCV)) PIX_PLANES_RGBA (32 bit interger per pixel (1 plane image in openCV)) Returns true if one of these formats. There is no check to prohibit a BW image to be changed to RBG or the other way. The image data is unchanged.

References colFormat, img, PIX_PLANES_BGGR, PIX_PLANES_BGR, PIX_PLANES_BGRA, PIX_PLANES_BW, PIX_PLANES_GBRG, PIX_PLANES_GRBG, PIX_PLANES_RGB, PIX_PLANES_RGBA, PIX_PLANES_RGGB, PIX_PLANES_YUV, PIX_PLANES_YUV420, and PIX_PLANES_YUV422.

bool UImage::setMaxSize43 ( )

Set size to the largest image that the buffer can hold when the width/height relation is 4/3. Returns true if this is possible (buffer can hold an image of 4x3 pixels)

References maxPixels(), roundi(), and setSize().

Referenced by clear(), GetNewNonCameraImage(), UHighGuiWindowHandle::makeImage(), and setROI().

void UImage::setName ( const char *  imageName)
inline
void UImage::setNameAndExt ( const char *  basename,
const char *  ext = NULL 
)

Set name and extension inside image meta data. to the attributes 'name' and 'saveType'. If no name is provided and no name exist already then a name is created using the image number on the form img99999. If no type is provided, and non existing, then the type is set to 'png'. On return there is a valid name and extension in the name and saveType fields.

References imageNumber, MAX_EXT_SIZE, MAX_IMG_NAME_SIZE, name, and saveType.

Referenced by UImAna::findContourPoly(), UImageAna::findContourPoly(), UImAna::findContourPolyCroma(), UImageAna::findContourPolyCroma(), UImagePoly::findContourPolyCroma(), UImAna::findRoadPoly(), UImageAna::findRoadPoly(), UImagePoly::findRoadPoly(), pixYUV(), and setROI().

void UImage::setPix ( unsigned int  line,
unsigned int  column,
UPixel  pix 
)
inline
void UImage::setPixChar ( unsigned int  line,
unsigned int  column,
char  pix 
)
inline

Set a pixel to this value (8-bit (char)).

Parameters
lineis row number starting at 0 counting down in image (less than height())
columnis coloumn starting at 0 counting positive right (less than width())
pixis the value to be set at this point

References getCharRef().

Referenced by UFuncImSeg::findBestCoooccurrence().

void UImage::setPixel ( int  x1,
int  y1,
UPixel  rgb,
UImage image = NULL,
int  procent = 0 
)

Paint one pixel in mixtuer of provided color and same pixel in this image or provided image

Referenced by inRange().

void UImage::setPixInt ( unsigned int  line,
unsigned int  column,
int  pix 
)
inline

Set a pixel to this value (32-bit int).

Parameters
lineis row number starting at 0 counting down in image (less than height())
columnis coloumn starting at 0 counting positive right (less than width())
pixis the value to be set at this point

References getIntRef().

void UImage::setPixUChar ( unsigned int  line,
unsigned int  column,
unsigned char  pix 
)
inline

Set a pixel to this value (8-bit unsigned).

Parameters
lineis row number starting at 0 counting down in image (less than height())
columnis coloumn starting at 0 counting positive right (less than width())
pixis the value to be set at this point

References getUCharRef().

Referenced by UResObj3d::doGndPlaneMask(), and UResObj3d::makeGroundPlaneProfileImage().

bool UImage::setQuadPix ( unsigned int  line,
unsigned int  column,
unsigned char  I11,
unsigned char  I12,
unsigned char  I21,
unsigned char  I22,
unsigned char  U,
unsigned char  V 
)

Set four intensity pixels and one set of color pixels The line and column will be truncated to even numbers. NB! works correct if format is YUV420 only!

References colFormat, getUline(), getVline(), getYline(), height(), PIX_PLANES_YUV420, and width().

Referenced by getBufferSize().

void UImage::setROI ( int  x,
int  y,
int  w,
int  h 
)
inline

Set Region of Interest for image processing using filter and other methods.

References img, setMaxSize43(), and setNameAndExt().

bool UImage::setSize ( const unsigned int  iHeight,
const unsigned int  iWidth,
const int  channels,
const int  depth,
const char *  colorType = NULL 
)

Initialize image size. Pixel depth is always unsigned byte.

Parameters
heightis height of image
widthis width of image (height * width * channels should be less than 800*600*3 = 1440000 (bytes)
channelsmay be 1,2,3,4 - default is 3 (usually RGB).
depthshould be 8 (bits) if channels > 1, else 16 is OK
colorTypeis a string with color type - valid types are: "BW", "RGB", "BGR", "YUV". "RGBA", "BGRA", "GRAY", "BW16S", "BGGR", "RGGB", "YUV420"
Returns
true if changes as requested

References getData(), img, maxBytes(), PIX_PLANES_BW, pu, pv, py, resizeBuffer(), and setColorType().

Referenced by UResObj3d::addGroundObjects(), UFuncKinect::callGotNewDataWithObject(), UImgProj::clearColMap(), UImgPolyProj::clearColMap(), UImgPolyProj::clearPathMap(), UImgProj::clearPathMap(), copyJustImage(), copyScaleDown(), UFuncStraightLine::crop(), UResObj3d::do3dVoxels(), UResObj3d::doGndPlaneMask(), UClientFuncLaserGui::doRepaint(), UFuncImSeg::findBestCoooccurrence(), UImageAna::findRoad(), UImageAna::findRoadCroma(), UImageAna::findRoadFill(), UCamDevGigE::frameToImage(), fromMat(), UFuncCropRow::handleCommand(), UFuncStraightLine::handleCommand(), UFunctionImgPool::handleImageGetCommand(), UClientFuncImage::handleImages(), initImage(), loadBMP(), loadPNG(), UResObj3d::makeGroundPlaneProfileImage(), UFuncPCLTest::MakeMap(), UProbGrid::makeProbGrid(), UProbGrid::makeProbGrid2(), UImagePoly::makeSimilarImage3(), UFuncBallKL::maskColors(), UFuncPiPi::maskColors(), UFuncBall::maskColors(), UFuncBall_improved::maskColors(), UFuncCropRow::maskColors(), UFuncLinefinder::maskColors(), moveBGGRtoBGR(), moveBGGRtoBW(), moveBGGRToHalfBGR(), moveBGGRtoRGB(), moveYUV420To(), moveYUV420ToHalf(), UCamDevGigE::openDeviceDefault(), UNavPaint::paint(), UResObj3d::paintGndPlane(), pixYUV(), UFuncTOF::processChannel8(), UFuncKinect::processDepthImages(), UFuncStereo::processImages(), UFuncTOF::processImages(), UCamPwc::readFramesThread(), UCamDevice::readFramesThread(), UFuncPTgrey::Receiver(), resize(), UFuncPiCam::run(), savePNG(), setMaxSize43(), UClientFuncImgGui::showUVImage(), UResDisp::showUVImage(), testCameraHDR(), testImageHandling(), testMatrixVecBig(), testOpenCv(), testOpticalFlow(), testOpticalFlowHarris(), testVideo(), testVideo2(), toBGR(), toBW(), toCromaBGR(), toRaibow(), toRaibowInv(), toRGB(), toRGBA(), toYUV(), unpackZLIB(), yuv422toBGR(), yuv422toBGRhalf(), yuv422toBW(), yuv422toRGB(), yuv422toRGBhalf(), yuv422toYUV(), yuv422toYUVhalf(), UCamDevGuppy::~UCamDevGuppy(), and UCamDevIeee1394::~UCamDevIeee1394().

bool UImage::setSizeOnly ( const unsigned int  iHeight,
const unsigned int  iWidth 
)

Change size only, i.e. keep depth, channels and color-mode. Returns true if space for new size. Do not change image content, and any existing image will be folded differently

References getData(), img, maxBytes(), pu, pv, py, and resizeBuffer().

Referenced by UFuncKinect::callGotNewDataWithObject(), copyToMaxRes(), UFuncImSeg::doLBPhistogramMatch(), UFunctionImgPool::handleImageGetCommand(), moveBWToHalf(), movePixToHalf(), UCamPwc::readFramesThread(), and UCamDevice::readFramesThread().

void UImage::shiftCols ( int  cols,
int  byteFill = -1 
)

Shift image this number of columns left or right. The shift is right if cols is positive. If byteFill is zero or positive the now empty part of the image is filled with this value.

References absi(), getChannels(), getLine(), height(), and width().

Referenced by getBufferSize(), and testImageShift().

void UImage::shiftRows ( int  rows,
int  byteFill = -1 
)

Shift image this number of rows up or down. The shift is down if rows is positive. If byteFill is zero or positive the now empty part of the image is filled with this value.

References absi(), getChannels(), getLine(), height(), and width().

Referenced by getBufferSize(), and testImageShift().

UPixel UImage::sobel ( UPixel p1,
UPixel p2,
UPixel p3 
)

Get edge pixel in area up to 3 pixels left of the 3 rows of pixels provided in these pointers. The center is assumed to be p2[1]. Returns the Sobel value of this pixel.

References absi(), mini(), UPixel::p1, UPixel::p2, and UPixel::p3.

Referenced by edgeSobel(), and getBufferSize().

UPixel UImage::sobel ( UPixel p1,
UPixel p2,
UPixel p3,
UPixel pixRef,
int  reducFactor 
)

Get edge pixel in area up to 3 pixels left of the 3 rows of pixels provided in these pointers. The center is assumed to be p2[1]. Returns a signed Sobel value added to the pixRef pixel value.

References maxi(), mini(), UPixel::p1, UPixel::p2, and UPixel::p3.

bool UImage::toBGR ( UImage dest = NULL)
bool UImage::toBW ( UImage dest = NULL)
int UImage::toColFormatInt ( const char *  col)
static

Convert color type string to integer value. Color format is not case sensitive. Does not change anything in image.

Parameters
colis string representation BW, gray, RGB, BGR, BW16s, RGGB BGGR BGRA RGBA YUV YUV420.
Returns
the ordinal value.

References colFormat, PIX_PLANES_BAYER, PIX_PLANES_BGGR, PIX_PLANES_BGR, PIX_PLANES_BGRA, PIX_PLANES_BW, PIX_PLANES_BW16S, PIX_PLANES_GBRG, PIX_PLANES_GRBG, PIX_PLANES_RGB, PIX_PLANES_RGBA, PIX_PLANES_RGGB, PIX_PLANES_YUV, PIX_PLANES_YUV420, and PIX_PLANES_YUV422.

Referenced by UFunctionImgPool::handleImageGetCommand(), and tone().

bool UImage::toCromaBGR ( UImage dest = NULL)

Conver image to an image, where the intensity is removed and replaced with BGR values, where the sum is always 256 (+/- 3) Returns true if converted.

References UPixel::asCromaBGR(), colFormat, copyMeta(), getData(), height(), isBayer(), isBGR(), isBW(), isRGB(), isYUV(), isYUV420(), moveYUV420To(), UPixel::p1, UPixel::p2, UPixel::p3, PIX_PLANES_BGR, PIX_PLANES_YUV420, PIX_PLANES_YUV422, UPixel::set(), setColorType(), setSize(), UPixel::setYUVto(), toBGR(), UPixel::u, UPixel::v, width(), and UPixel::y.

Referenced by UFuncFz::doClassify(), UClientFuncImgGui::showUVImage(), testCromaImage(), and updated().

bool UImage::toHalf ( )

Downscale image to half size, if image is YUV420 or one of the bayer formats, then the resulting image is in BGR format. Does nothing if format is YUV.

Returns
true

References colFormat, getUCharRef(), height(), isYUV(), moveBGGRToHalfBGR(), moveBWToHalf(), movePixToHalf(), moveYUV420ToHalf(), PIX_PLANES_BGGR, PIX_PLANES_BW, PIX_PLANES_GBRG, PIX_PLANES_GRBG, PIX_PLANES_RGB, PIX_PLANES_RGGB, PIX_PLANES_YUV420, PIX_PLANES_YUV422, setColorType(), width(), and yuv422toRGBhalf().

Referenced by getImageTime(), testVideo3(), UCamDevGuppy::~UCamDevGuppy(), and UCamDevIeee1394::~UCamDevIeee1394().

bool UImage::toMat ( )

make a cv:Mat copy og this image - to be used in opencv2 and 3 methods. This will make a separate copy of the image to a new buffer, and the new buffer will not be available on the for UImage operations until data is moved back with a fromMat() call. Only images with 1 and 3 channels can be converted (e.g. RGB and 8bit gray images)

Returns
true if conversion is sucessfull

References getChannels(), getData(), getDepth(), height(), mat, and width().

Referenced by getConvertBuffer(), and UFuncImSeg::makeLBPimage().

void UImage::tone ( UPixel rgb,
int  procent 
)
void UImage::tone ( UPixel  rgb,
int  procent 
)
inline
bool UImage::toRaibow ( UImage gray)

Make this image a rainbow RGB image from the BW image provided. 0 towards 255 in gray becomes white->red->green->mag->dark->black.

Parameters
graythe gray sourceimage.
Returns
true if success.

References getData(), getUCharRef(), height(), setSize(), and width().

Referenced by getImageTime(), and UFuncStereo::processImages().

bool UImage::toRaibowInv ( UImage gray)

Make this image a rainbow RGB image from the BW image provided. 255 towards 0 in gray becomes white->red->green->mag->dark->black.

Parameters
graythe gray sourceimage.
Returns
true if success.

References getData(), getUCharRef(), height(), setSize(), and width().

Referenced by getImageTime().

bool UImage::toRGB ( UImage dest = NULL)
bool UImage::toRGBA ( UImage dest = NULL)
bool UImage::toYUV ( UImage dest = NULL)
bool UImage::unpackZLIB ( int  rows,
int  cols,
const char *  colFormat,
char *  buffer,
int  bufferCnt 
)

Unpack image data original image height and width must be provided along with color type - see setColorType(). The buffer must hold the packed image to unpack (assumed packed using packZLIB). bufferCnt is the length of the bufferdata to use.

References getChannels(), getData(), height(), imgBytes(), maxBytes(), setSize(), unpackZlib(), and width().

Referenced by isTooBig(), and testZlib().

void UImage::updated ( )
inline

Mark the image as updated, i.e. increase the used number, so that debug users can see the updated image. Further set the update time almost the same purpose. The 'used' count is a bit depricated.

References colourSaturate(), imgUpdated(), toBGR(), toBW(), toCromaBGR(), toRGB(), toRGBA(), and toYUV().

Referenced by UResObj3d::addGroundObjects(), UFuncCog::calculateCOG(), UFuncKinect::callGotNewDataWithObject(), UFuncCropRow::CannyEdge(), UFuncStraightLine::crop(), UFuncKinect::decodeReplayLine(), UImagePool::decodeReplayLine(), UCamPool::decodeReplayLine(), UResObj3d::do3dVoxels(), UFuncFz::doClassify(), UResObj3d::doGndPlaneMask(), UFuncImSeg::doGrayLevelCooccurenceMatrix(), UFuncImSeg::doLBPhistogramMatch(), UFuncLinefinder::filterMask(), UFuncBallKL::findBall(), UFuncPiPi::findBall(), UFuncBall::findBall(), UFuncBall_improved::findBall(), UFuncImSeg::findBestCoooccurrence(), fromMat(), UFuncStraightLine::GLR(), UFuncCropRow::handleCommand(), UFuncStraightLine::handleCommand(), UFunctionImage::handleImageGetCommand(), UFunctionImgPool::handleImageGetCommand(), UFunctionImgPool::handleImageSetCommand(), UFuncLinefinder::houghTest(), UResDisp::loadImgToPool(), UResObj3d::makeGroundPlaneProfileImage(), UFuncImSeg::makeLBPimage(), UFuncPCLTest::MakeMap(), UFuncBallKL::maskColors(), UFuncPiPi::maskColors(), UFuncBall::maskColors(), UFuncBall_improved::maskColors(), UFuncCropRow::maskColors(), UFuncLinefinder::maskColors(), UFuncImSeg::meanShiftSegment(), UFuncFz::paintColoredImage(), UResObj3d::paintGndPlane(), UResObj3d::paintPolygonInImage(), UFuncStraightLine::printLine(), UFuncTOF::processChannel8(), UFuncKinect::processDepthImages(), UFuncStereo::processImages(), UFuncTOF::processImages(), UFuncPTgrey::Receiver(), UCamRad::removeRadialError(), UFuncPiCam::run(), UResDisp::showUVImage(), UFuncStraightLine::threshold(), toBW(), UFuncV4lGst::useBuffer(), UCamDevGuppy::~UCamDevGuppy(), and UCamDevIeee1394::~UCamDevIeee1394().

void UImage::vLine ( unsigned int  col,
unsigned int  r1,
unsigned int  r2,
int  p1,
int  p2,
int  p3 
)

Paint vertical line in one or more of the image planes from row 'r1' to row 'r2'. paint with value p1, p2, p3 in the 3 planes, if a plane is -1 (negative) then plane is not changed.

References getLine(), height(), maxi(), mini(), UPixel::p1, UPixel::p2, UPixel::p3, and width().

Referenced by getBufferSize().

unsigned int UImage::width ( )
inline

Get image width in pixels.

References img.

Referenced by UFuncCog::calculateCOG(), UFuncFocus::calculateFocusValue(), clear(), colourSaturate(), UFuncImSeg::cooccurrence(), copyAndScale(), copyJustImage(), copyMeta(), copyScaleDown(), copyToMaxRes(), UImAna::distFilt(), UImageAna::distFilt(), UImagePoly::distFilt(), UImAna::distFiltH(), UImageAna::distFiltH(), UImagePoly::distFiltH(), UCalibrationComponents::doFindCodeCellIntensity(), UClientFuncImgGui::doFuzzyClassify(), UClientFuncLaserGui::doImage(), UFuncImSeg::doLBPhistogramMatch(), UFuncImSeg::doPatchHistogram(), UFuncImSeg::doPatchHistogramLBP8(), UImgPolyProj::doPolygonMap(), UImgProj::doPolygonMap(), UImgPolyProj::doProject(), UImgProj::doProject(), UClientFuncLaserGui::doRepaint(), edgeSobel(), UCalibrationComponents::EnumerateCalibrationDetections(), UCalibrationComponents::EnumerateCalibrationDetections4(), UFuncImgPoly::findAreaFromSeedRGB(), UFuncBallKL::findBall(), UFuncBall::findBall(), UFuncBall_improved::findBall(), UCalibrate::findBarcodeChartPosition(), UImAna::findContour(), UImageAna::findContour(), UImAna::findContourPoly(), UImageAna::findContourPoly(), UImAna::findContourPolyCroma(), UImageAna::findContourPolyCroma(), UImagePoly::findContourPolyCroma(), UCalibrate::findGmk(), UFunctionCamPath::findPath(), UImageAna::findRoad(), UImageAna::findRoadCroma(), UImageAna::findRoadFill(), UImAna::findRoadPoly(), UImageAna::findRoadPoly(), UImagePoly::findRoadPoly(), UFuncImSeg::findSegments(), UResCamIfImg::getImageBuffer(), getPix(), getPixInt(), getQuadPix(), UImAna::getRoadProbability(), UImageAna::getRoadProbability(), UImagePoly::getRoadProbability(), getUline(), getVline(), UClientFuncImage::gotNewImage(), gridLine(), UFuncCropRow::handleCommand(), UFunctionImgPool::handleImageListCommand(), UFuncImgPoly::handleImgPolyCommand(), UFunctionCamPath::handlePathGetCommand(), harris(), harris2(), harris3(), hLine(), UImageAna::imageContour2(), UImagePoly::imageContour2(), UImAna::imageContourMaha(), UImageAna::imageContourMaha(), UImagePoly::imageContourMaha(), UImAna::imageContourMahaCroma(), UImageAna::imageContourMahaCroma(), UImagePoly::imageContourMahaCroma(), UImAna::imageUsable(), UImageAna::imageUsable(), UImagePoly::imageUsable(), imgBytes(), UImgPush::imgUpdated(), UFuncFz::initializeClassesFromLine(), invertY(), lineInGrid(), loadBMP(), UFuncFz::loadNewImage(), loadPNG(), UFuncImSeg::makeLBPimage(), UFuncKinect::makeObj3Dcloud(), UProbGrid::makeProbGrid(), UProbGrid::makeProbGrid2(), UImagePoly::makeSimilarImage2(), UImagePoly::makeSimilarImage3(), UCalibrate::MarkCornerDetections4(), UFuncImSeg::meanShiftSegment(), median(), UNavPaint::mousePan(), UNavPaint::mouseScale(), moveBGGRtoBGR(), moveBGGRtoBW(), moveBGGRToHalfBGR(), moveBGGRtoRGB(), moveBW16ToRGB(), moveBWToHalf(), movePixToHalf(), moveYUV420To(), moveYUV420ToHalf(), UNavPaint::paint(), UClientFuncImgGui::paintClustPixels(), UFuncFz::paintClustPixels(), UFuncFz::paintColoredImage(), UGroundPatches::paintDebugGrid(), UClientFuncLaserGui::paintEkfData(), UNavPaint::paintFeatures(), UClientFuncLaserGui::paintFreePoly(), UResObj3d::paintGndPlane(), UProbGrid::paintGrid(), UImgPolyProj::paintGrid(), UImgProj::paintGrid(), UClientFuncLaserGui::paintHistScan(), UClientFuncLaserGui::paintLineSegments(), UClientFuncLaserGui::paintObstGrp(), UClientFuncLaserGui::paintOdoData(), UClientFuncLaserGui::paintOdoDest(), UClientFuncLaserGui::paintOdoGrid(), UClientFuncLaserGui::paintPathData(), UClientFuncLaserGui::paintPis(), UClientFuncLaserGui::paintPostHistLine(), UImAna::paintRoadImage(), UImageAna::paintRoadImage(), UImagePoly::paintRoadImage(), UNavPaint::paintScanStatData(), UClientFuncLaserGui::paintScanStatData(), UGrid3D::paintVoxels(), UClientFuncLaserGui::paintWpc(), UClientFuncLaserGui::paintWpListData(), pixYUV(), UFuncStereo::processImages(), UImgPush::run(), UFuncV4lGst::run(), UImgPush::runShow(), saveBMP(), UProbGrid::saveMatlab(), savePNG(), saveTxt(), UFunctionImgBase::sendImage(), setQuadPix(), shiftCols(), shiftRows(), UClientFuncImgGui::showFocusNumber(), UHighGuiWindowHandle::showImage(), UClientFuncImgGui::showLine(), UClientFuncImgGui::showUVImage(), UResDisp::showUVImage(), testEigenvector(), testMatrixVecBig(), testOpenCv(), testZlib(), toBGR(), toBW(), toCromaBGR(), toHalf(), toMat(), tone(), toRaibow(), toRaibowInv(), toRGB(), toRGBA(), toYUV(), unpackZLIB(), UQtgui::updateImg(), MainWindow::updateImg(), UFuncV4lGst::useBuffer(), and vLine().

bool UImage::yuv422toBGR ( uint8_t *  source,
int  h,
int  w 
)

Move a source YUV422 image buffer of known size to an BGR image. NB source buffer must not be the same as the image buffer in this image

Parameters
sourceis a buffer with the source values
his the source image height in rows
wis source image width
Returns
true if successfull

References getLine(), PIX_PLANES_RGB, setColorType(), setSize(), UPixel::YUVtoBGR(), and UPixel::YUVtoRGB().

Referenced by toBGR().

bool UImage::yuv422toBGRhalf ( uint8_t *  source,
int  h,
int  w 
)

Move a source YUV422 image buffer of known size to an BGR image in half resolution.

Parameters
sourceis a buffer with the source values
his the source image height in rows
wis source image width
Returns
true if successfull

References getLine(), PIX_PLANES_RGB, setColorType(), setSize(), and UPixel::YUVtoBGR().

bool UImage::yuv422toBW ( uint8_t *  source,
int  h,
int  w 
)

Move a source YUV422 image buffer of known size to an BW image.

Parameters
sourceis a buffer with the source values
his the source image height in rows
wis source image width
Returns
true if successfull

References getLine(), PIX_PLANES_BW, setColorType(), and setSize().

Referenced by toBW().

bool UImage::yuv422toRGB ( uint8_t *  source,
int  h,
int  w 
)

Move a source YUV422 image buffer of known size to an RGB image. NB source buffer must not be the same as the image buffer in this image

Parameters
sourceis a buffer with the source values
his the source image height in rows
wis source image width
Returns
true if successfull

References getLine(), PIX_PLANES_RGB, setColorType(), setSize(), and UPixel::YUVtoRGB().

Referenced by toRGB(), and toRGBA().

bool UImage::yuv422toRGBhalf ( uint8_t *  source,
int  h,
int  w 
)

Move a source YUV422 image buffer of known size to an RGB image in half resolution.

Parameters
sourceis a buffer with the source values
his the source image height in rows
wis source image width
Returns
true if successfull

References getLine(), PIX_PLANES_RGB, setColorType(), setSize(), and UPixel::YUVtoRGB().

Referenced by toHalf().

bool UImage::yuv422toYUV ( uint8_t *  source,
int  h,
int  w 
)

Move a source YUV422 image buffer of known size to an YUV image. NB source buffer must not be the same as the image buffer in this image

Parameters
sourceis a buffer with the source values
his the source image height in rows
wis source image width
Returns
true if successfull

References getLine(), PIX_PLANES_YUV, UPixel::set(), setColorType(), and setSize().

Referenced by toYUV().

bool UImage::yuv422toYUVhalf ( uint8_t *  source,
int  h,
int  w 
)

Move a source YUV422 image buffer of known size to an YUV image in half resolution. NB source buffer must not be the same as the image buffer in this image

Parameters
sourceis a buffer with the source values
his the source image height in rows
wis source image width
Returns
true if successfull

References getLine(), PIX_PLANES_YUV, UPixel::set(), setColorType(), and setSize().

Member Data Documentation

unsigned int UImage::bufferBytes
protected

Size of allocated buffer to img.imageBuffer

Referenced by initImage(), maxBytes(), maxPixels(), resize(), resizeBuffer(), and UImage().

void* UImage::cam
int UImage::camDevice

Camera device number

Referenced by UResObj3d::addGroundObjects(), UFuncKinect::callGotNewDataWithObject(), copyMeta(), UFuncKinect::decodeReplayLine(), UImagePool::decodeReplayLine(), UResObj3d::do3dVoxels(), UResObj3d::doGndPlaneMask(), UFuncImgPoly::findAreaFromSeedRGB(), UFunctionCamPath::findPath(), UCamDevGigE::frameToImage(), UFunctionCamBase::getCamAndRawImage(), UFunctionCamBase::getImage(), UResCamIfImg::gotNewImage(), UFuncRectify::handleCommand(), UFuncBall_improved::handleCommand(), UFuncBallKL::handleCommand(), UFuncBall::handleCommand(), UFuncCropRow::handleCommand(), UFuncStraightLine::handleCommand(), UFuncLinefinder::handleCommand(), UFuncFz::handleCommand(), UFunctionCamGmk::handleGmkGetCommand(), UFunctionImage::handleImageGetCommand(), UFunctionImgPool::handleImageGetCommand(), UClientFuncImage::handleImages(), UFunctionImgPool::handleImageSetCommand(), UFunctionCamPath::handlePathGetCommand(), UImageLog::logImage(), UFuncPiCam::logImageToFile(), UFuncPTgrey::logImageToFile(), UFuncKinect::logImageToFile(), UFuncTOF::logImageToFile(), UImageLog::logImgPoolImage(), UFuncKinect::makeObj3Dcloud(), UCamDevGigE::openDeviceDefault(), UResObj3d::paintGndPlane(), UFuncTOF::processChannel8(), UFuncStereo::processImages(), UFuncTOF::processImages(), UCamPwc::readFramesThread(), UCamDevice::readFramesThread(), UFuncPTgrey::Receiver(), UFuncPiCam::run(), UFunctionImgBase::sendImage(), UFuncV4lGst::useBuffer(), UCamDevGuppy::~UCamDevGuppy(), and UCamDevIeee1394::~UCamDevIeee1394().

int UImage::colFormat
protected
UImage* UImage::convertBuffer
private

private format conversion buffer - created if needed

Referenced by getConvertBuffer(), moveBGGRtoBGR(), moveBGGRtoRGB(), savePNG(), toRGB(), toRGBA(), toYUV(), UImage(), and ~UImage().

unsigned int UImage::hdrSet

High dynamic range set number. 0 is a normal image not part of a set. 1 is a dark reference image (minimum shutter time) 2.. is images with increasing shutter time and/or gain, so hdrSet 2 should not be saturated and hdrSet = 3 shuld be usabel in saddows.

Referenced by copyMeta().

unsigned long UImage::imageNumber
IplImage UImage::img
protected
UTime UImage::imgTime

Estimated time image were taken

Referenced by UResObj3d::addGroundObjects(), UFuncKinect::callGotNewDataWithObject(), UFuncCog::centerOfGravity(), copyMeta(), copyScaleDown(), UFuncKinect::decodeReplayLine(), UImagePool::decodeReplayLine(), UCamPool::decodeReplayLine(), UResObj3d::do3dVoxels(), UResObj3d::doGndPlaneMask(), UClientFuncLaserGui::doImage(), UFuncImgPoly::findAreaFromSeedRGB(), UFuncBallKL::findBall(), UFuncPiPi::findBall(), UFuncBall::findBall(), UFuncBall_improved::findBall(), UImAna::findContourPoly(), UImageAna::findContourPoly(), UImAna::findContourPolyCroma(), UImageAna::findContourPolyCroma(), UImagePoly::findContourPolyCroma(), UCalibrate::findGmk(), UFunctionCamPath::findPath(), UFuncCropRow::findPlants(), UFuncTracking::FirstImage(), UCamDevGigE::frameToImage(), getImageTime(), GetNewNonCameraImage(), UResCamIfImg::gotNewImage(), UFuncCropRow::handleCommand(), UFunctionImage::handleImageGetCommand(), UFunctionImgPool::handleImageGetCommand(), UClientFuncImage::handleImages(), UFunctionImgPool::handleImageSetCommand(), UFunctionCamPath::handlePathGetCommand(), UFuncLinefinder::houghTest(), UImgPush::imgUpdated(), UImageLog::logImage(), UFuncKinect::makeObj3Dcloud(), UNavPaint::paint(), UResObj3d::paintGndPlane(), UFuncTOF::processChannel8(), UFuncStereo::processImages(), UFuncTOF::processImages(), UCamPwc::readFramesThread(), UCamDevice::readFramesThread(), UFuncPTgrey::Receiver(), UFuncPiCam::run(), UClientFuncImgGui::saveImage(), UFunctionImgBase::sendImage(), UHighGuiWindowHandle::showImage(), testImageHandling(), testImageLoadSave(), testMatrixVecBig(), UFuncTracking::TrackObjects(), UImage(), UFuncV4lGst::useBuffer(), UCamDevGuppy::~UCamDevGuppy(), and UCamDevIeee1394::~UCamDevIeee1394().

UTime UImage::imgUpdateTime
protected

additional timestamp for other purposes than when image was taken

Referenced by UImgPush::fillBuffer(), UImgPush::fillShowBuffer(), getUpdatedTime(), and imgUpdated().

cv::Mat UImage::mat
char UImage::name[MAX_IMG_NAME_SIZE]
UPosition UImage::pos
unsigned char* UImage::pu
protected

first value of U-pixels (YUV 420 planar only)

Referenced by getUline(), moveYUV420ToHalf(), setSize(), and setSizeOnly().

unsigned char* UImage::pv
protected

first value of V pixels (YUV 420 planar only)

Referenced by getVline(), moveYUV420ToHalf(), setSize(), and setSizeOnly().

unsigned char* UImage::py
protected

first value of Y-pixels (YUV 420 planar only)

Referenced by getYline(), setSize(), and setSizeOnly().

bool UImage::radialErrorRemoved
float UImage::readDelay

Read delay is an indication of the validity of the image timestamp. If the delay is wery short (< 5ms) it is likely that the image were on stock before the timestamping and therefore older than could be expected from the timestamp.

Referenced by copyMeta(), UCamPwc::readFramesThread(), and UCamDevice::readFramesThread().

URotation UImage::rot
char UImage::saveType[MAX_EXT_SIZE]

Image saved using this file type e.g. png or bmp etc.

Referenced by copyMeta(), copyScaleDown(), GetNewNonCameraImage(), pixYUV(), setNameAndExt(), and UImage().

int UImage::source

Source number - used for processed images only (default value is image pool number). Value is not handled by copy functions.

Referenced by colorSaturate(), UImagePool::getImage(), UFunctionImgPool::handleImageGetCommand(), UClientFuncImage::handleImages(), and UImage().

unsigned int UImage::used
bool UImage::valid

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