Classes | |
| struct | CameraInfo |
| Camera Calibration info. More... | |
| struct | IPMInfo |
| struct | LaneDetectorConf |
| Structure to hold lane detector settings. More... | |
| struct | Line |
| Line structure with start and end points. More... | |
| struct | LineState_ |
| struct | Spline |
| Spline structure. More... | |
Typedefs | |
| typedef struct LaneDetector::CameraInfo | CameraInfo |
| Camera Calibration info. | |
| typedef enum LaneDetector::CheckSplineStatus_ | CheckSplineStatus |
| typedef struct LaneDetector::IPMInfo | IPMInfo |
| typedef struct LaneDetector::LaneDetectorConf | LaneDetectorConf |
| Structure to hold lane detector settings. | |
| typedef struct LaneDetector::Line | Line |
| Line structure with start and end points. | |
| typedef enum LaneDetector::LineColor_ | LineColor |
| Line color. | |
| typedef struct LaneDetector::LineState_ | LineState |
| typedef enum LaneDetector::LineType_ | LineType |
| Line type. | |
| typedef struct LaneDetector::Spline | Spline |
| Spline structure. | |
Enumerations | |
| enum | CheckSplineStatus_ { ShortSpline = 0x1, CurvedSpline = 0x2, CurvedSplineTheta = 0x4, HorizontalSpline = 0x8 } |
| enum | LineColor_ { LINE_COLOR_NONE, LINE_COLOR_YELLOW, LINE_COLOR_WHITE } |
Line color. More... | |
| enum | LineType_ { LINE_HORIZONTAL = 0, LINE_VERTICAL = 1 } |
Line type. More... | |
Functions | |
| void | dummy () |
| void | imageCallback (const sensor_msgs::ImageConstPtr &original_image) |
| CvPoint2D32f | mcvAddVector (CvPoint2D32f v1, CvPoint2D32f v2) |
| void | mcvBinarizeImage (CvMat *inImage) |
| void | mcvCheckLaneWidth (vector< Line > &lines, vector< float > &scores, float wMu, float wSigma) |
| This function takes a bunch of lines, and check which 2 lines can make a lane. | |
| bool | mcvCheckMergeLines (const Line &line1, const Line &line2, float thetaThreshold, float rThreshold) |
| bool | mcvCheckMergeSplines (const Spline &sp1, const Spline &sp2, float thetaThreshold, float rThreshold, float meanThetaThreshold, float meanRThreshold, float centroidThreshold) |
| int | mcvCheckPoints (const CvMat *points) |
| int | mcvCheckSpline (const Spline &spline, float curvenessThreshold, float lengthThreshold, float thetaDiffThreshold, float thetaThreshold) |
| int | mcvChooseBestPeak (const vector< CvPoint2D32f > &peaks, const vector< float > &peakVals, CvPoint2D32f &peak, float &peakVal, float contThreshold, const CvPoint2D32f &tangent, const CvPoint2D32f &prevPoint, float angleThreshold) |
| void | mcvCumSum (const CvMat *inMat, CvMat *outMat) |
| void | mcvDrawLine (CvMat *image, Line line, CvScalar color, int width) |
| void | mcvDrawRectangle (CvMat *image, CvRect rect, CvScalar color, int width) |
| void | mcvDrawSpline (CvMat *image, Spline spline, CvScalar color, int width) |
| void | mcvDrawText (CvMat *image, char *str, CvPoint point, float size, CvScalar color) |
| CvMat * | mcvEvalBezierSpline (const Spline &spline, float h, CvMat *tangents) |
| CvMat * | mcvExtendPoints (const CvMat *im, const CvMat *inPoints, float angleThreshold, float meanDirAngleThreshold, int linePixelsTangent, int linePixelsNormal, float contThreshold, int deviationThreshold, CvRect bbox, bool smoothPeaks) |
| void | mcvFilterLines (const CvMat *inImage, CvMat *outImage, unsigned char wx, unsigned char wy, FLOAT sigmax, FLOAT sigmay, LineType lineType) |
| Spline | mcvFitBezierSpline (CvMat *points, int degree) |
| void | mcvFitRansacLine (const CvMat *image, int numSamples, int numIterations, float threshold, float scoreThreshold, int numGoodFit, bool getEndPoints, LineType lineType, Line *lineXY, float *lineRTheta, float *lineScore) |
| void | mcvFitRansacSpline (const CvMat *image, int numSamples, int numIterations, float threshold, float scoreThreshold, int numGoodFit, int splineDegree, float h, Spline *spline, float *splineScore, int splineScoreJitter, float splineScoreLengthRatio, float splineScoreAngleRatio, float splineScoreStep, vector< Spline > *prevSplines) |
| void | mcvFitRobustLine (const CvMat *points, float *lineRTheta, float *lineAbc) |
| void | mcvGet2DerivativeGaussianKernel (CvMat *kernel, unsigned char w, FLOAT sigma) |
| CvMat * | mcvGetBezierSplinePixels (Spline &spline, float h, CvSize box, bool extendSpline) |
| Line | mcvGetExtendedNormalLine (CvPoint2D32f &curPoint, CvPoint2D32f &tangent, int linePixelsTangent, int linePixelsNormal, CvPoint2D32f &nextPoint) |
| void | mcvGetGaussianKernel (CvMat *kernel, unsigned char w, FLOAT sigma) |
| void | mcvGetHoughTransformLines (const CvMat *inImage, vector< Line > *lines, vector< FLOAT > *lineScores, FLOAT rMin, FLOAT rMax, FLOAT rStep, FLOAT thetaMin, FLOAT thetaMax, FLOAT thetaStep, bool binarize, bool localMaxima, FLOAT detectionThreshold, bool smoothScores, bool group, FLOAT groupThreshold) |
| void | mcvGetHVLines (const CvMat *inImage, vector< Line > *lines, vector< FLOAT > *lineScores, LineType lineType, FLOAT linePixelWidth, bool binarize, bool localMaxima, FLOAT detectionThreshold, bool smoothScores) |
| void | mcvGetIPM (const CvMat *inImage, CvMat *outImage, IPMInfo *ipmInfo, const CameraInfo *cameraInfo, list< CvPoint > *outPoints) |
| void | mcvGetIPMExtent (const CameraInfo *cameraInfo, IPMInfo *ipmInfo) |
| vector< int > | mcvGetJitterVector (int maxJitter) |
| void | mcvGetLanes (const CvMat *inImage, const CvMat *clrImage, vector< Line > *lanes, vector< FLOAT > *lineScores, vector< Spline > *splines, vector< float > *splineScores, CameraInfo *cameraInfo, LaneDetectorConf *stopLineConf, LineState *state) |
| float | mcvGetLineAngle (const Line &line) |
| void | mcvGetLineExtent (const CvMat *im, const Line &inLine, Line &outLine) |
| float | mcvGetLinePeak (const CvMat *im, const Line &line, vector< CvPoint2D32f > &peaks, vector< float > &peakVals, bool positivePeak, bool smoothPeaks) |
| CvMat * | mcvGetLinePixels (const Line &line) |
| void | mcvGetLines (const CvMat *image, LineType lineType, vector< Line > &lines, vector< float > &lineScores, vector< Spline > &splines, vector< float > &splineScores, LaneDetectorConf *lineConf, LineState *state) |
| void | mcvGetLinesBoundingBoxes (const vector< Line > &lines, LineType type, CvSize size, vector< CvRect > &boxes) |
| This function extracts bounding boxes from lines. | |
| double | mcvGetLocalMaxSubPixel (double val1, double val2, double val3) |
| void | mcvGetMatLocalMax (const CvMat *inMat, vector< double > &localMaxima, vector< CvPoint > &localMaximaLoc, double threshold) |
| void | mcvGetMatMax (const CvMat *inMat, vector< double > &maxima, vector< CvPoint > &maximaLoc, double threshold) |
| CvMat * | mcvGetNonZeroPoints (const CvMat *inMat, bool floatMat) |
| LineColor | mcvGetPointsColor (const CvMat *im, const CvMat *points, int window, float numYellowMin, float rgMin, float rgMax, float gbMin, float rbMin, bool rbf, float rbfThreshold) |
| void | mcvGetPointsFeatures (const CvMat *points, CvPoint2D32f *centroid, float *theta, float *r, float *length, float *meanTheta, float *meanR, float *curveness) |
| CvPoint2D32f | mcvGetPointsMeanVector (const CvMat *points, bool forward) |
| FLOAT | mcvGetQuantile (const CvMat *mat, FLOAT qtile) |
| void | mcvGetRansacLines (const CvMat *im, vector< Line > &lines, vector< float > &lineScores, LaneDetectorConf *lineConf, LineType lineType) |
| void | mcvGetRansacSplines (const CvMat *im, vector< Line > &lines, vector< float > &lineScores, LaneDetectorConf *lineConf, LineType lineType, vector< Spline > &splines, vector< float > &splineScores, LineState *state) |
| void | mcvGetSplineFeatures (const Spline &spline, CvPoint2D32f *centroid, float *theta, float *r, float *length, float *meanTheta, float *meanR, float *curveness) |
| void | mcvGetSplinesBoundingBoxes (const vector< Spline > &splines, LineType type, CvSize size, vector< CvRect > &boxes) |
| This function extracts bounding boxes from splines. | |
| float | mcvGetSplineScore (const CvMat *image, Spline &spline, float h, int jitterVal, float lengthRatio, float angleRatio) |
| void | mcvGetStopLines (const CvMat *inImage, vector< Line > *stopLines, vector< float > *lineScores, const CameraInfo *cameraInfo, LaneDetectorConf *stopLineConf) |
| void | mcvGetStopLines (const CvMat *inImage, vector< Line > *stopLines, vector< FLOAT > *lineScores, const CameraInfo *cameraInfo, LaneDetectorConf *stopLineConf) |
| FLOAT_POINT2D | mcvGetVanishingPoint (const CameraInfo *cameraInfo) |
| void | mcvGetVectorLocalMax (const CvMat *inVec, vector< double > &localMaxima, vector< int > &localMaximaLoc) |
| void | mcvGetVectorMax (const CvMat *inVector, double *max, int *maxLoc, int ignore) |
| float | mcvGetVectorNorm (const CvPoint2D32f &v) |
| void | mcvGroupBoundingBoxes (vector< CvRect > &boxes, LineType type, float groupThreshold) |
| This function groups together bounding boxes. | |
| void | mcvGroupLines (vector< Line > &lines, vector< float > &lineScores, float groupThreshold, CvSize bbox) |
| void | mcvGroupSplines (vector< Spline > &splines, vector< float > &scores) |
| void | mcvInitCameraInfo (char *const fileName, CameraInfo *cameraInfo) |
| void | mcvInitLaneDetectorConf (char *const fileName, LaneDetectorConf *stopLineConf) |
| void | mcvIntersectLineRThetaWithBB (FLOAT r, FLOAT theta, const CvSize bbox, Line *outLine) |
| void | mcvIntersectLineRThetaWithRect (FLOAT r, FLOAT theta, const Line &rect, Line &outLine) |
| void | mcvIntersectLineWithBB (const Line *inLine, const CvSize bbox, Line *outLine) |
| bool | mcvIsPointInside (FLOAT_POINT2D &point, const CvRect &rect) |
| bool | mcvIsPointInside (FLOAT_POINT2D &point, const Line &rect) |
| bool | mcvIsPointInside (FLOAT_POINT2D point, CvSize bbox) |
| bool | mcvIsValidPeak (const CvPoint2D32f &peak, const CvPoint2D32f &tangent, const CvPoint2D32f &prevPoint, float angleThreshold) |
| void | mcvLines2Mat (const vector< Line > *lines, CvMat *mat) |
| void | mcvLinesImIPM2Im (vector< Line > &lines, IPMInfo &ipmInfo, CameraInfo &cameraInfo, CvSize imSize) |
| void | mcvLineXY2RTheta (const Line &line, float &r, float &theta) |
| Spline | mcvLineXY2Spline (const Line &line, int degree) |
| void | mcvLoadImage (const char *filename, CvMat **clrImage, CvMat **channelImage) |
| void | mcvLocalizePoints (const CvMat *im, const CvMat *inPoints, CvMat *outPoints, int numLinePixels, float angleThreshold) |
| void | mcvMat2Lines (const CvMat *mat, vector< Line > *lines) |
| void | mcvMatInt2Float (const CvMat *inMat, CvMat *outMat) |
| CvPoint2D32f | mcvMultiplyVector (CvPoint2D32f v, float s) |
| CvPoint2D32f | mcvNormalizeVector (float x, float y) |
| CvPoint2D32f | mcvNormalizeVector (const CvPoint &v) |
| CvPoint2D32f | mcvNormalizeVector (const CvPoint2D32f &v) |
| void | mcvPointImIPM2World (FLOAT_POINT2D *point, const IPMInfo *ipmInfo) |
| void | mcvPostprocessLines (const CvMat *image, const CvMat *clrImage, const CvMat *rawipm, const CvMat *fipm, vector< Line > &lines, vector< float > &lineScores, vector< Spline > &splines, vector< float > &splineScores, LaneDetectorConf *lineConf, LineState *state, IPMInfo &ipmInfo, CameraInfo &cameraInfo) |
| void | mcvSampleWeighted (const CvMat *cumSum, int numSamples, CvMat *randInd, CvRNG *rng) |
| void | mcvScaleCameraInfo (CameraInfo *cameraInfo, CvSize size) |
| void | mcvScaleMat (const CvMat *inMat, CvMat *outMat) |
| void | mcvSetMat (CvMat *inMat, CvRect mask, double val) |
| void | mcvSortPoints (const CvMat *inPoints, CvMat *outPoints, int dim, int dir) |
| void | mcvSplinesImIPM2Im (vector< Spline > &splines, IPMInfo &ipmInfo, CameraInfo &cameraInfo, CvSize imSize) |
| CvPoint2D32f | mcvSubtractVector (const CvPoint2D32f &v1, const CvPoint2D32f &v2) |
| void | mcvThresholdLower (const CvMat *inMat, CvMat *outMat, FLOAT threshold) |
| void | mcvTransformGround2Image (const CvMat *inPoints, CvMat *outPoints, const CameraInfo *cameraInfo) |
| void | mcvTransformImage2Ground (const CvMat *inPoints, CvMat *outPoints, const CameraInfo *cameraInfo) |
| void | mcvTransformImIPM2Ground (const CvMat *inMat, CvMat *outMat, const IPMInfo *ipmInfo) |
| void | mcvTransformImIPM2Im (const CvMat *inMat, CvMat *outMat, const IPMInfo *ipmInfo, const CameraInfo *cameraInfo) |
| template<class T > | |
| CvMat * | mcvVector2Mat (const vector< T > &vec) |
| void | ProcessImage (const char *filename, CameraInfo &cameraInfo, LaneDetectorConf &lanesConf, LaneDetectorConf &stoplinesConf, gengetopt_args_info &options, ofstream *outputFile=NULL, int index=0, clock_t *elapsedTime=NULL) |
| bool | ReadLines (const char *filename, vector< string > *lines) |
| void | SHOT_MAT_TYPE (const CvMat *pmat) |
| void | SHOW_IMAGE (Mat pmat, char str[]) |
| void | SHOW_IMAGE (const IplImage *pmat, char str[]) |
| void | SHOW_IMAGE (const CvMat *pmat, const char str[], int wait) |
| void | SHOW_LINE (const Line line, char str[]) |
| void | SHOW_MAT (const CvMat *pmat, char str[]) |
| void | SHOW_POINT (const FLOAT_POINT2D pt, char str[]) |
| void | SHOW_RECT (const CvRect rect, char str[]) |
| void | SHOW_SPLINE (const Spline spline, char str[]) |
Variables | |
| int | DEBUG_LINES = 0 |
| typedef struct LaneDetector::CameraInfo LaneDetector::CameraInfo |
Camera Calibration info.
| typedef struct LaneDetector::IPMInfo LaneDetector::IPMInfo |
Structure to hold the info about IPM transformation
| typedef struct LaneDetector::LaneDetectorConf LaneDetector::LaneDetectorConf |
Structure to hold lane detector settings.
| typedef struct LaneDetector::Line LaneDetector::Line |
Line structure with start and end points.
| typedef enum LaneDetector::LineColor_ LaneDetector::LineColor |
Line color.
| typedef struct LaneDetector::LineState_ LaneDetector::LineState |
Structure to hold state used for initializing the next detection process from a previous one
| typedef enum LaneDetector::LineType_ LaneDetector::LineType |
Line type.
| typedef struct LaneDetector::Spline LaneDetector::Spline |
Spline structure.
Definition at line 70 of file LaneDetector.hh.
Line color.
Definition at line 27 of file LaneDetector.hh.
| void LaneDetector::dummy | ( | ) |
Definition at line 7342 of file LaneDetector.cpp.
| void LaneDetector::imageCallback | ( | const sensor_msgs::ImageConstPtr & | original_image | ) |
| CvPoint2D32f LaneDetector::mcvAddVector | ( | CvPoint2D32f | v1, | |
| CvPoint2D32f | v2 | |||
| ) |
This functions adds two vectors and returns the result
| v1 | the first vector | |
| v2 | the second vector |
| void LaneDetector::mcvBinarizeImage | ( | CvMat * | inImage | ) |
This function binarizes the input image i.e. nonzero elements becomen 1 and others are 0.
| inImage | input & output image |
This function binarizes the input image i.e. nonzero elements become 1 and others are 0.
| inImage | input & output image |
| void LaneDetector::mcvCheckLaneWidth | ( | vector< Line > & | lines, | |
| vector< float > & | scores, | |||
| float | wMu, | |||
| float | wSigma | |||
| ) |
This function takes a bunch of lines, and check which 2 lines can make a lane.
| lines | vector of lines | |
| scores | vector of line scores | |
| wMu | expected lane width | |
| wSigma | std deviation of lane width |
| bool LaneDetector::mcvCheckMergeLines | ( | const Line & | line1, | |
| const Line & | line2, | |||
| float | thetaThreshold, | |||
| float | rThreshold | |||
| ) |
This functions checks if to merge two splines or not
| line1 | the first line | |
| line2 | the second line | |
| thetaThreshold | Angle threshold for merging splines (radians) | |
| rThreshold | R threshold (distance from origin) for merginn splines |
| bool LaneDetector::mcvCheckMergeSplines | ( | const Spline & | sp1, | |
| const Spline & | sp2, | |||
| float | thetaThreshold, | |||
| float | rThreshold, | |||
| float | meanThetaThreshold, | |||
| float | meanRThreshold, | |||
| float | centroidThreshold | |||
| ) |
This functions checks if to merge two splines or not
| sp1 | the first spline | |
| sp2 | the second spline | |
| thetaThreshold | Angle threshold for merging splines (radians) | |
| rThreshold | R threshold (distance from origin) for merginn splines | |
| MeanhetaThreshold | Mean angle threshold for merging splines (radians) | |
| MeanRThreshold | Mean r threshold (distance from origin) for merginn splines | |
| centroidThreshold | Distance threshold between spline cetroids for merging |
| int LaneDetector::mcvCheckPoints | ( | const CvMat * | points | ) |
This function makes some checks on points and decides whether to keep them or not
| points | the array of points to check |
| int LaneDetector::mcvCheckSpline | ( | const Spline & | spline, | |
| float | curvenessThreshold, | |||
| float | lengthThreshold, | |||
| float | thetaDiffThreshold, | |||
| float | thetaThreshold | |||
| ) |
This function makes some checks on splines and decides whether to keep them or not
| spline | the input spline | |
| curvenessThreshold | minimum curveness score it should have | |
| lengthThreshold | mimimum threshold it should have | |
| thetaDiffThreshold | max theta diff it should have | |
| thetaThreshold | max theta it should have to be considered horizontal |
| int LaneDetector::mcvChooseBestPeak | ( | const vector< CvPoint2D32f > & | peaks, | |
| const vector< float > & | peakVals, | |||
| CvPoint2D32f & | peak, | |||
| float & | peakVal, | |||
| float | contThreshold, | |||
| const CvPoint2D32f & | tangent, | |||
| const CvPoint2D32f & | prevPoint, | |||
| float | angleThreshold | |||
| ) |
This functions chooses the best peak that minimizes deviation from the tangent direction given
| peaks | the peaks found | |
| peakVals | the values for the peaks | |
| peak | the returned peak | |
| peakVal | the peak value for chosen peak, -1 if nothing | |
| contThreshold | the threshold to get peak above | |
| tangent | the tangent line along which the peak was found normal to (normalized) | |
| prevPoint | the previous point along the tangent | |
| angleThreshold | the angle threshold to consider for valid peaks |
| void LaneDetector::mcvCumSum | ( | const CvMat * | inMat, | |
| CvMat * | outMat | |||
| ) |
This function computes the cumulative sum for a vector
| inMat | input matrix | |
| outMat | output matrix |
| void LaneDetector::mcvDrawLine | ( | CvMat * | image, | |
| Line | line, | |||
| CvScalar | color, | |||
| int | width | |||
| ) |
This function draws a line onto the passed image
| image | the input iamge | |
| line | input line | |
| line | color | |
| width | line width |
| void LaneDetector::mcvDrawRectangle | ( | CvMat * | image, | |
| CvRect | rect, | |||
| CvScalar | color, | |||
| int | width | |||
| ) |
This function draws a rectangle onto the passed image
| image | the input iamge | |
| rect | the input rectangle | |
| color | the rectangle color | |
| width | the rectangle width |
This function draws a rectangle onto the passed image
| image | the input image | |
| rect | the input rectangle | |
| color | the rectangle color | |
| width | the rectangle width |
| void LaneDetector::mcvDrawSpline | ( | CvMat * | image, | |
| Spline | spline, | |||
| CvScalar | color, | |||
| int | width | |||
| ) |
This function draws a spline onto the passed image
| image | the input iamge | |
| spline | input spline | |
| spline | color |
| void LaneDetector::mcvDrawText | ( | CvMat * | image, | |
| char * | str, | |||
| CvPoint | point, | |||
| float | size, | |||
| CvScalar | color | |||
| ) |
This function draws a spline onto the passed image
| image | the input iamge | |
| str | the string to put | |
| point | the point where to put the text | |
| size | the font size | |
| color | the font color |
| CvMat * LaneDetector::mcvEvalBezierSpline | ( | const Spline & | spline, | |
| float | h, | |||
| CvMat * | tangents | |||
| ) |
This function evaluates Bezier spline with given resolution
| spline | input spline | |
| h | the input resolution | |
| tangents | compute tangents at the two endpoints [t0; t1] |
This function evaluates Bezier spline with given resolution
| spline | input spline | |
| h | the input resolution | |
| tangents | the tangents at the two end-points of the spline [t0; t1] |
| CvMat * LaneDetector::mcvExtendPoints | ( | const CvMat * | im, | |
| const CvMat * | inPoints, | |||
| float | angleThreshold, | |||
| float | meanDirAngleThreshold, | |||
| int | linePixelsTangent, | |||
| int | linePixelsNormal, | |||
| float | contThreshold, | |||
| int | deviationThreshold, | |||
| CvRect | bbox, | |||
| bool | smoothPeaks | |||
| ) |
This functions extends the given set of points in both directions to extend curves and lines in the image
| im | the input image | |
| inPoints | the input points Nx2 matrix of points | |
| angleThreshold | angle threshold used for extending | |
| meanDirAngleThreshold | angle threshold from mean direction | |
| linePixelsTangent | number of pixels to go in tangent direction | |
| linePixelsNormal | number of pixels to go in normal direction | |
| contThreshold | number of pixels to go in tangent direction | |
| deviationThreshold | Stop extending when number of deviating points exceeds this threshold | |
| bbox | a bounding box not to get points outside | |
| smoothPeak | whether to smooth for calculating peaks or not |
| void LaneDetector::mcvFilterLines | ( | const CvMat * | inImage, | |
| CvMat * | outImage, | |||
| unsigned char | wx, | |||
| unsigned char | wy, | |||
| FLOAT | sigmax, | |||
| FLOAT | sigmay, | |||
| LineType | lineType | |||
| ) |
This function filters the input image looking for horizontal or vertical lines with specific width or height.
| inImage | the input image | |
| outImage | the output image in IPM | |
| wx | width of kernel window in x direction = 2*wx+1 (default 2) | |
| wy | width of kernel window in y direction = 2*wy+1 (default 2) | |
| sigmax | std deviation of kernel in x (default 1) | |
| sigmay | std deviation of kernel in y (default 1) | |
| lineType | type of the line LINE_HORIZONTAL (default) LINE_VERTICAL |
| Spline LaneDetector::mcvFitBezierSpline | ( | CvMat * | points, | |
| int | degree | |||
| ) |
This function fits a Bezier spline to the passed input points
| points | the input points | |
| degree | the required spline degree |
| void LaneDetector::mcvFitRansacLine | ( | const CvMat * | image, | |
| int | numSamples, | |||
| int | numIterations, | |||
| float | threshold, | |||
| float | scoreThreshold, | |||
| int | numGoodFit, | |||
| bool | getEndPoints, | |||
| LineType | lineType, | |||
| Line * | lineXY, | |||
| float * | lineRTheta, | |||
| float * | lineScore | |||
| ) |
This functions implements RANSAC algorithm for line fitting given an image
| image | input image | |
| numSamples | number of samples to take every iteration | |
| numIterations | number of iterations to run | |
| threshold | threshold to use to assess a point as a good fit to a line | |
| numGoodFit | number of points close enough to say there's a good fit | |
| getEndPoints | whether to get the end points of the line from the data, just intersect with the image boundaries | |
| lineType | the type of line to look for (affects getEndPoints) | |
| lineXY | the fitted line | |
| lineRTheta | the fitted line [r; theta] | |
| lineScore | the score of the line detected |
| void LaneDetector::mcvFitRansacSpline | ( | const CvMat * | image, | |
| int | numSamples, | |||
| int | numIterations, | |||
| float | threshold, | |||
| float | scoreThreshold, | |||
| int | numGoodFit, | |||
| int | splineDegree, | |||
| float | h, | |||
| Spline * | spline, | |||
| float * | splineScore, | |||
| int | splineScoreJitter, | |||
| float | splineScoreLengthRatio, | |||
| float | splineScoreAngleRatio, | |||
| float | splineScoreStep, | |||
| vector< Spline > * | prevSplines | |||
| ) |
This functions implements RANSAC algorithm for spline fitting given an image
| image | input image | |
| numSamples | number of samples to take every iteration | |
| numIterations | number of iterations to run | |
| threshold | threshold to use to assess a point as a good fit to a line | |
| numGoodFit | number of points close enough to say there's a good fit | |
| splineDegree | the spline degree to fit | |
| h | the resolution to use for splines | |
| spline | the fitted line | |
| splineScore | the score of the line detected | |
| splineScoreJitter | Number of pixels to go around the spline to compute score | |
| splineScoreLengthRatio | Ratio of spline length to use | |
| splineScoreAngleRatio | Ratio of spline angle to use | |
| splineScoreStep | Step to use for spline score computation | |
| prevSplines | the splines from the previous frame, to use as initial seeds pass NULL to ignore this input |
| void LaneDetector::mcvFitRobustLine | ( | const CvMat * | points, | |
| float * | lineRTheta, | |||
| float * | lineAbc | |||
| ) |
This functions fits a line using the orthogonal distance to the line by minimizing the sum of squares of this distance.
| points | the input points to fit the line to which is 2xN matrix with x values on first row and y values on second | |
| lineRTheta | the return line [r, theta] where the line is x*cos(theta)+y*sin(theta)=r | |
| lineAbc | the return line in [a, b, c] where the line is a*x+b*y+c=0 |
| void LaneDetector::mcvGet2DerivativeGaussianKernel | ( | CvMat * | kernel, | |
| unsigned char | w, | |||
| FLOAT | sigma | |||
| ) |
This function gets a 1-D second derivative gaussian filter with specified std deviation and range
| kernel | input mat to hold the kernel (2*w+1x1) column vector (already allocated) | |
| w | width of kernel is 2*w+1 | |
| sigma | std deviation |
| CvMat * LaneDetector::mcvGetBezierSplinePixels | ( | Spline & | spline, | |
| float | h, | |||
| CvSize | box, | |||
| bool | extendSpline | |||
| ) |
This function returns pixel coordinates for the Bezier spline with the given resolution.
| spline | input spline | |
| h | the input resolution | |
| box | the bounding box | |
| extendSpline | whether to extend spline with straight lines or not (default false) |
| Line LaneDetector::mcvGetExtendedNormalLine | ( | CvPoint2D32f & | curPoint, | |
| CvPoint2D32f & | tangent, | |||
| int | linePixelsTangent, | |||
| int | linePixelsNormal, | |||
| CvPoint2D32f & | nextPoint | |||
| ) |
This functions extends a point along the tangent and gets the normal line at the new point
| curPoint | the current point to extend | |
| tangent | the tangent at this point (not necessarily normalized) | |
| linePixelsTangent | the number of pixels to go in tangent direction | |
| linePixelsNormal | the number of pixels to go in normal direction | |
| nextPoint | the next point on the extended line |
This functions extends a point along the tangent and gets the normal line at the new point
| curPoint | the current point to extend | |
| tangent | the tangent at this point (not necessarily normalized) | |
| linePixelsTangent | the number of pixels to go in tangent direction | |
| linePixelsNormal | the number of pixels to go in normal direction |
| void LaneDetector::mcvGetGaussianKernel | ( | CvMat * | kernel, | |
| unsigned char | w, | |||
| FLOAT | sigma | |||
| ) |
This function gets a 1-D gaussian filter with specified std deviation and range
| kernel | input mat to hold the kernel (2*w+1x1) column vector (already allocated) | |
| w | width of kernel is 2*w+1 | |
| sigma | std deviation |
| void LaneDetector::mcvGetHoughTransformLines | ( | const CvMat * | inImage, | |
| vector< Line > * | lines, | |||
| vector< FLOAT > * | lineScores, | |||
| FLOAT | rMin, | |||
| FLOAT | rMax, | |||
| FLOAT | rStep, | |||
| FLOAT | thetaMin, | |||
| FLOAT | thetaMax, | |||
| FLOAT | thetaStep, | |||
| bool | binarize, | |||
| bool | localMaxima, | |||
| FLOAT | detectionThreshold, | |||
| bool | smoothScores, | |||
| bool | group, | |||
| FLOAT | groupThreshold | |||
| ) |
This function detects lines in images using Hough transform
| inImage | input image | |
| lines | vector of lines to hold the results | |
| lineScores | scores of the detected lines (vector of floats) | |
| rMin | minimum r use for finding the lines (default 0) | |
| rMax | maximum r to find (default max(size(im))) | |
| rStep | step to use for binning (default is 2) | |
| thetaMin | minimum angle theta to look for (default 0) all in radians | |
| thetaMax | maximum angle theta to look for (default 2*pi) | |
| thetaStep | step to use for binning theta (default 5) | |
| binarize | if to binarize the input image or use the raw values so that non-zero values are not treated as equal | |
| localMaxima | whether to detect local maxima or just get the maximum | |
| detectionThreshold | threshold for detection | |
| smoothScores | whether to smooth scores detected or not | |
| group | whether to group nearby detections (1) or not (0 default) | |
| groupThreshold | the minimum distance used for grouping (default 10) |
2;
| void LaneDetector::mcvGetHVLines | ( | const CvMat * | inImage, | |
| vector< Line > * | lines, | |||
| vector< FLOAT > * | lineScores, | |||
| LineType | lineType, | |||
| FLOAT | linePixelWidth, | |||
| bool | binarize, | |||
| bool | localMaxima, | |||
| FLOAT | detectionThreshold, | |||
| bool | smoothScores | |||
| ) |
This function groups the input filtered image into horizontal or vertical lines.
| inImage | input image | |
| lines | returned detected lines (vector of points) | |
| lineScores | scores of the detected lines (vector of floats) | |
| lineType | type of lines to detect LINE_HORIZONTAL (default) or LINE_VERTICAL | |
| linePixelWidth | width (or height) of lines to detect | |
| localMaxima | whether to detect local maxima or just get the maximum | |
| detectionThreshold | threshold for detection | |
| smoothScores | whether to smooth scores detected or not |
| void LaneDetector::mcvGetIPM | ( | const CvMat * | inImage, | |
| CvMat * | outImage, | |||
| IPMInfo * | ipmInfo, | |||
| const CameraInfo * | cameraInfo, | |||
| list< CvPoint > * | outPoints | |||
| ) |
This function returns the Inverse Perspective Mapping of the input image, assuming a flat ground plane, and given the camera parameters.
| inImage | the input image | |
| outImage | the output image in IPM | |
| ipmInfo | the returned IPM info for the transformation | |
| focalLength | focal length (in x and y direction) | |
| cameraInfo | the camera parameters | |
| outPoints | indices of points outside the image |
This function returns the Inverse Perspective Mapping of the input image, assuming a flat ground plane, and given the camera parameters.
| inImage | the input image | |
| outImage | the output image in IPM | |
| ipmInfo | the returned IPM info for the transformation | |
| focalLength | focal length (in x and y direction) | |
| cameraInfo | the camera parameters |
| void LaneDetector::mcvGetIPMExtent | ( | const CameraInfo * | cameraInfo, | |
| IPMInfo * | ipmInfo | |||
| ) |
Gets the extent of the image on the ground plane given the camera parameters
| cameraInfo | the input camera info | |
| ipmInfo | the IPM info containing the extent on ground plane: xLimits & yLimits only are changed |
| vector< int > LaneDetector::mcvGetJitterVector | ( | int | maxJitter | ) |
This functions returns a vector of jitter from the input maxJitter value This is used for computing spline scores for example, to get scores around the rasterization of the spline
| maxJitter | the max value to look around |
| void LaneDetector::mcvGetLanes | ( | const CvMat * | inImage, | |
| const CvMat * | clrImage, | |||
| vector< Line > * | lanes, | |||
| vector< FLOAT > * | lineScores, | |||
| vector< Spline > * | splines, | |||
| vector< float > * | splineScores, | |||
| CameraInfo * | cameraInfo, | |||
| LaneDetectorConf * | stopLineConf, | |||
| LineState * | state | |||
| ) |
This function detects lanes in the input image using IPM transformation and the input camera parameters. The returned lines are in a vector of Line objects, having start and end point in input image frame.
| image | the input image | |
| lanes | a vector of returned stop lines in input image coordinates | |
| linescores | a vector of line scores returned | |
| cameraInfo | the camera parameters | |
| stopLineConf | parameters for stop line detection | |
| state | returns the current state and inputs the previous state to initialize the current detection (NULL to ignore) |
| float LaneDetector::mcvGetLineAngle | ( | const Line & | line | ) |
This functions gets the angle of the line with the horizontal
| line | the line |
| void LaneDetector::mcvGetLineExtent | ( | const CvMat * | im, | |
| const Line & | inLine, | |||
| Line & | outLine | |||
| ) |
This functions implements Bresenham's algorithm for getting pixels of the line given its two endpoints
| im | the input image | |
| inLine | the input line | |
| outLine | the output line |
This functions implements Bresenham's algorithm for getting pixels of the line given its two endpoints
| line | the input line | |
| x | a vector of x locations for the line pixels (0-based) | |
| y | a vector of y locations for the line pixels (0-based) This functions implements Bresenham's algorithm for getting pixels of the line given its two endpoints | |
| im | the input image | |
| inLine | the input line | |
| outLine | the output line |
| float LaneDetector::mcvGetLinePeak | ( | const CvMat * | im, | |
| const Line & | line, | |||
| vector< CvPoint2D32f > & | peaks, | |||
| vector< float > & | peakVals, | |||
| bool | positivePeak, | |||
| bool | smoothPeaks | |||
| ) |
This functions gets the point on the input line that matches the peak in the input image, where the peak is the middle of a bright line on dark background in the image
| im | the input image | |
| line | input line | |
| peaks | a vector of peak outputs | |
| peakVals | the values for each of these peaks | |
| positivePeak | whether we are looking for positive or negative peak(default true) | |
| smoothPeaks | whether to smooth pixels for calculating peaks or not |
| CvMat * LaneDetector::mcvGetLinePixels | ( | const Line & | line | ) |
This functions implements Bresenham's algorithm for getting pixels of the line given its two endpoints
| line | the input line |
| void LaneDetector::mcvGetLines | ( | const CvMat * | image, | |
| LineType | lineType, | |||
| vector< Line > & | lines, | |||
| vector< float > & | lineScores, | |||
| vector< Spline > & | splines, | |||
| vector< float > & | splineScores, | |||
| LaneDetectorConf * | lineConf, | |||
| LineState * | state | |||
| ) |
This function extracts lines from the passed infiltered and thresholded image
| image | the input thresholded filtered image | |
| lineType | the line type to look for (LINE_VERTICAL or LINE_HORIZONTAL) | |
| lines | a vector of lines | |
| lineScores | the line scores | |
| splines | a vector of returned splines | |
| splineScores | the spline scores | |
| lineConf | the conf structure | |
| state | the state for RANSAC splines |
| void LaneDetector::mcvGetLinesBoundingBoxes | ( | const vector< Line > & | lines, | |
| LineType | type, | |||
| CvSize | size, | |||
| vector< CvRect > & | boxes | |||
| ) |
This function extracts bounding boxes from lines.
| lines | vector of lines | |
| type | the type of lines (LINE_HORIZONTAL or LINE_VERTICAL) | |
| size | the size of image containing the lines | |
| boxes | a vector of output bounding boxes |
| double LaneDetector::mcvGetLocalMaxSubPixel | ( | double | val1, | |
| double | val2, | |||
| double | val3 | |||
| ) |
This fits a parabola to the entered data to get the location of local maximum with sub-pixel accuracy
| val1 | first value | |
| val2 | second value | |
| val3 | third value |
| void LaneDetector::mcvGetMatLocalMax | ( | const CvMat * | inMat, | |
| vector< double > & | localMaxima, | |||
| vector< CvPoint > & | localMaximaLoc, | |||
| double | threshold | |||
| ) |
This function gets the local maxima in a matrix and their positions and its location
| inMat | input matrix | |
| localMaxima | the output vector of local maxima | |
| localMaximaLoc | the vector of locations of the local maxima, where each location is cvPoint(x=col, y=row) zero-based |
This function gets the local maxima in a matrix and their positions and its location
| inMat | input matrix | |
| localMaxima | the output vector of local maxima | |
| localMaximaLoc | the vector of locations of the local maxima, where each location is cvPoint(x=col, y=row) zero-based | |
| threshold | threshold to return local maxima above |
| void LaneDetector::mcvGetMatMax | ( | const CvMat * | inMat, | |
| vector< double > & | maxima, | |||
| vector< CvPoint > & | maximaLoc, | |||
| double | threshold | |||
| ) |
This function gets the locations and values of all points above a certain threshold
| inMat | input matrix | |
| maxima | the output vector of maxima | |
| maximaLoc | the vector of locations of the maxima, where each location is cvPoint(x=col, y=row) zero-based |
This function gets the locations and values of all points above a certain threshold
| inMat | input matrix | |
| maxima | the output vector of maxima | |
| maximaLoc | the vector of locations of the maxima, where each location is cvPoint(x=col, y=row) zero-based | |
| threshold | the threshold to get all points above |
| CvMat * LaneDetector::mcvGetNonZeroPoints | ( | const CvMat * | inMat, | |
| bool | floatMat | |||
| ) |
This function gets the indices of the non-zero values in a matrix
| inMat | the input matrix | |
| outMat | the output matrix, with 2xN containing the x and y in each column and the pixels value [xs; ys; pixel values] | |
| floatMat | whether to return floating points or integers for the outMat |
This function gets the indices of the non-zero values in a matrix
| inMat | the input matrix | |
| outMat | the output matrix, with 2xN containing the x and y in each column | |
| floatMat | whether to return floating points or integers for the outMat |
| LineColor LaneDetector::mcvGetPointsColor | ( | const CvMat * | im, | |
| const CvMat * | points, | |||
| int | window, | |||
| float | numYellowMin, | |||
| float | rgMin, | |||
| float | rgMax, | |||
| float | gbMin, | |||
| float | rbMin, | |||
| bool | rbf, | |||
| float | rbfThreshold | |||
| ) |
This functions classifies the passed points according to their color to be either white, yellow, or neither
| im | the input color image | |
| points | the array of points | |
| window | the window to use | |
| numYellowMin | min percentage of yellow points | |
| rgMin | ||
| rgMax | ||
| gbMin | ||
| rbMin |
| void LaneDetector::mcvGetPointsFeatures | ( | const CvMat * | points, | |
| CvPoint2D32f * | centroid, | |||
| float * | theta, | |||
| float * | r, | |||
| float * | length, | |||
| float * | meanTheta, | |||
| float * | meanR, | |||
| float * | curveness | |||
| ) |
This functions computes some features for a set of points
| points | the input points | |
| centroid | the computed centroid of the points | |
| theta | the major orientation of the points (angle of line joining first and last points, angle as in Hough Transform lines) | |
| r | distance from origin for line from first to last point | |
| length | the length of the line from first to last point | |
| meanTheta | the average orientation of the points (by computing mean theta for line segments form the points) | |
| meanR | the average distance from the origin of the points (the same computations as for meanTheta) | |
| curveness | computes the angle between vectors of points, which gives an indication of the curveness of the spline -1-->1 with 1 best and -1 worst |
| CvPoint2D32f LaneDetector::mcvGetPointsMeanVector | ( | const CvMat * | points, | |
| bool | forward | |||
| ) |
This functions gets the average direction of the set of points by computing the mean vector between points
| points | the input points [Nx2] matrix | |
| forward | go forward or backward in computation (default true) |
| FLOAT LaneDetector::mcvGetQuantile | ( | const CvMat * | mat, | |
| FLOAT | qtile | |||
| ) |
This function gets the qtile-th quantile of the input matrix
| mat | input matrix | |
| qtile | required input quantile probability |
| void LaneDetector::mcvGetRansacLines | ( | const CvMat * | im, | |
| vector< Line > & | lines, | |||
| vector< float > & | lineScores, | |||
| LaneDetectorConf * | lineConf, | |||
| LineType | lineType | |||
| ) |
This function performs a RANSAC validation step on the detected lines
| image | the input image | |
| inLines | vector of lines | |
| outLines | vector of grouped lines | |
| groupThreshold | the threshold used for grouping | |
| bbox | the bounding box to intersect with | |
| lineType | the line type to work on (horizontal or vertical) |
This function performs a RANSAC validation step on the detected lines
| im | the input image | |
| lines | vector of input lines | |
| lineScores | the scores of input lines | |
| lineConf | the parameters controlling its operation | |
| lineType | the type of line to work on (LINE_HORIZONTAL or LINE_VERTICAL) |
| void LaneDetector::mcvGetRansacSplines | ( | const CvMat * | im, | |
| vector< Line > & | lines, | |||
| vector< float > & | lineScores, | |||
| LaneDetectorConf * | lineConf, | |||
| LineType | lineType, | |||
| vector< Spline > & | splines, | |||
| vector< float > & | splineScores, | |||
| LineState * | state | |||
| ) |
This function performs a RANSAC validation step on the detected lines to get splines
| image | the input image | |
| lines | vector of input lines to refine | |
| lineSCores | the line scores input | |
| groupThreshold | the threshold used for grouping | |
| bbox | the bounding box to intersect with | |
| lineType | the line type to work on (horizontal or vertical) | |
| prevSplines | the previous splines to use in initializing the detection |
| void LaneDetector::mcvGetSplineFeatures | ( | const Spline & | spline, | |
| CvPoint2D32f * | centroid, | |||
| float * | theta, | |||
| float * | r, | |||
| float * | length, | |||
| float * | meanTheta, | |||
| float * | meanR, | |||
| float * | curveness | |||
| ) |
This functions computes some features for the spline
| spline | the input spline | |
| centroid | the computed centroid of spline (mean of control points) | |
| theta | the major orientation of the spline (angle of line joining first and last control points, angle as in Hough Transform lines) | |
| r | distance from origin for line from first to last control point | |
| length | the length of the line from first to last control point | |
| meanTheta | the average orientation of the spline (by computing mean theta for line segments form the spline) | |
| meanR | the average distance from the origin of the spline (the same computations as for meanTheta) | |
| curveness | computes the angle between vectors of control points, which gives an indication of the curveness of the spline -1-->1 with 1 best and -1 worst |
| void LaneDetector::mcvGetSplinesBoundingBoxes | ( | const vector< Spline > & | splines, | |
| LineType | type, | |||
| CvSize | size, | |||
| vector< CvRect > & | boxes | |||
| ) |
This function extracts bounding boxes from splines.
| splines | vector of splines | |
| type | the type of lines (LINE_HORIZONTAL or LINE_VERTICAL) | |
| size | the size of image containing the lines | |
| boxes | a vector of output bounding boxes |
| float LaneDetector::mcvGetSplineScore | ( | const CvMat * | image, | |
| Spline & | spline, | |||
| float | h, | |||
| int | jitterVal, | |||
| float | lengthRatio, | |||
| float | angleRatio | |||
| ) |
This functions computes the score of the given spline from the input image
| image | the input image | |
| spline | the input spline | |
| h | spline resolution | |
| jitterVal | the amounts to count scores around the spline in x & y directions | |
| lengthRatio | the ratio to add to score from the spline length | |
| angleRatio | the ratio to add to score from spline curvature measure |
| void LaneDetector::mcvGetStopLines | ( | const CvMat * | inImage, | |
| vector< Line > * | stopLines, | |||
| vector< float > * | lineScores, | |||
| const CameraInfo * | cameraInfo, | |||
| LaneDetectorConf * | stopLineConf | |||
| ) |
This function detects stop lines in the input image using IPM transformation and the input camera parameters. The returned lines are in a vector of Line objects, having start and end point in input image frame.
| image | the input image | |
| stopLines | a vector of returned stop lines in input image coordinates | |
| linescores | a vector of line scores returned | |
| cameraInfo | the camera parameters | |
| stopLineConf | parameters for stop line detection |
| void LaneDetector::mcvGetStopLines | ( | const CvMat * | inImage, | |
| vector< Line > * | stopLines, | |||
| vector< FLOAT > * | lineScores, | |||
| const CameraInfo * | cameraInfo, | |||
| LaneDetectorConf * | stopLineConf | |||
| ) |
This function detects stop lines in the input image using IPM transformation and the input camera parameters. The returned lines are in a vector of Line objects, having start and end point in input image frame.
| image | the input image | |
| stopLines | a vector of returned stop lines in input image coordinates | |
| linescores | a vector of line scores returned | |
| cameraInfo | the camera parameters | |
| stopLineConf | parameters for stop line detection |
Definition at line 1256 of file LaneDetector.cpp.
| FLOAT_POINT2D LaneDetector::mcvGetVanishingPoint | ( | const CameraInfo * | cameraInfo | ) |
Computes the vanishing point in the image plane uv. It is the point of intersection of the image plane with the line in the XY-plane in the world coordinates that makes an angle yaw clockwise (form Y-axis) with Y-axis
| cameraInfo | the input camera parameter |
| void LaneDetector::mcvGetVectorLocalMax | ( | const CvMat * | inVec, | |
| vector< double > & | localMaxima, | |||
| vector< int > & | localMaximaLoc | |||
| ) |
This function gets the local maxima in a vector and their positions
| inVec | input vector | |
| localMaxima | the output vector of local maxima | |
| localMaximaLoc | the vector of locations of the local maxima, |
| void LaneDetector::mcvGetVectorMax | ( | const CvMat * | inVector, | |
| double * | max, | |||
| int * | maxLoc, | |||
| int | ignore = 0 | |||
| ) |
This function gets the maximum value in a vector (row or column) and its location
| inVector | the input vector | |
| max | the output max value | |
| maxLoc | the location (index) of the first max | |
| ignore | don't the first and last ignore elements |
| float LaneDetector::mcvGetVectorNorm | ( | const CvPoint2D32f & | v | ) |
This functions computes the vector norm
| v | input vector |
This functions computes the vector norm
| v | input vectpr |
| void LaneDetector::mcvGroupBoundingBoxes | ( | vector< CvRect > & | boxes, | |
| LineType | type, | |||
| float | groupThreshold | |||
| ) |
This function groups together bounding boxes.
| size | the size of image containing the lines | |
| boxes | a vector of output grouped bounding boxes | |
| type | the type of lines (LINE_HORIZONTAL or LINE_VERTICAL) | |
| groupThreshold | the threshold used for grouping (ratio of overlap) | |
| size | the size of image containing the lines | |
| boxes | a vector of output grouped bounding boxes * | |
| type | the type of lines (LINE_HORIZONTAL or LINE_VERTICAL) | |
| groupThreshold | the threshold used for grouping (ratio of overlap) |
| void LaneDetector::mcvGroupLines | ( | vector< Line > & | lines, | |
| vector< float > & | lineScores, | |||
| float | groupThreshold, | |||
| CvSize | bbox | |||
| ) |
This function groups nearby lines
| lines | vector of lines | |
| lineScores | scores of input lines | |
| groupThreshold | the threshold used for grouping | |
| bbox | the bounding box to intersect with |
This function groups nearby lines
| inLines | vector of lines | |
| outLines | vector of grouped lines | |
| groupThreshold | the threshold used for grouping | |
| bbox | the bounding box to intersect with |
| void LaneDetector::mcvGroupSplines | ( | vector< Spline > & | splines, | |
| vector< float > & | scores | |||
| ) |
This function groups nearby splines
| splines | vector of splines | |
| lineScores | scores of input lines |
| void LaneDetector::mcvInitCameraInfo | ( | char *const | fileName, | |
| CameraInfo * | cameraInfo | |||
| ) |
Initializes the cameraInfo structure with data read from the conf file
| fileName | the input camera conf file name | |
| cameraInfo | the returned camera parametrs struct |
| void LaneDetector::mcvInitLaneDetectorConf | ( | char *const | fileName, | |
| LaneDetectorConf * | stopLineConf | |||
| ) |
This initializes the LaneDetectorinfo structure
| fileName | the input file name | |
| stopLineConf | the structure to fill |
| void LaneDetector::mcvIntersectLineRThetaWithBB | ( | FLOAT | r, | |
| FLOAT | theta, | |||
| const CvSize | bbox, | |||
| Line * | outLine | |||
| ) |
This function intersects the input line (given in r and theta) with the given bounding box where the line is represented by: x cos(theta) + y sin(theta) = r
| r | the r value for the input line | |
| theta | the theta value for the input line | |
| bbox | the bounding box | |
| outLine | the output line |
| void LaneDetector::mcvIntersectLineRThetaWithRect | ( | FLOAT | r, | |
| FLOAT | theta, | |||
| const Line & | rect, | |||
| Line & | outLine | |||
| ) |
This function intersects the input line (given in r and theta) with the given rectangle where the line is represented by: x cos(theta) + y sin(theta) = r
| r | the r value for the input line | |
| theta | the theta value for the input line | |
| rect | the input rectangle (given two opposite points in the rectangle, upperleft->startPoint and bottomright->endPoint where x->right and y->down) | |
| outLine | the output line |
| void LaneDetector::mcvIntersectLineWithBB | ( | const Line * | inLine, | |
| const CvSize | bbox, | |||
| Line * | outLine | |||
| ) |
This function intersects the input line with the given bounding box
| inLine | the input line | |
| bbox | the bounding box | |
| outLine | the output line |
| bool LaneDetector::mcvIsPointInside | ( | FLOAT_POINT2D & | point, | |
| const CvRect & | rect | |||
| ) |
This function checks if the given point is inside the rectangle specified
| inLine | the input line | |
| rect | the specified rectangle |
| bool LaneDetector::mcvIsPointInside | ( | FLOAT_POINT2D & | point, | |
| const Line & | rect | |||
| ) |
This function checks if the given point is inside the rectangle specified
| inLine | the input line | |
| rect | the specified rectangle |
| bool LaneDetector::mcvIsPointInside | ( | FLOAT_POINT2D | point, | |
| CvSize | bbox | |||
| ) |
This function checks if the given point is inside the bounding box specified
| inLine | the input line | |
| bbox | the bounding box | |
| outLine | the output line |
| bool LaneDetector::mcvIsValidPeak | ( | const CvPoint2D32f & | peak, | |
| const CvPoint2D32f & | tangent, | |||
| const CvPoint2D32f & | prevPoint, | |||
| float | angleThreshold | |||
| ) |
This functions checks the peak point if much change in orientation
| peak | the input peak point | |
| tangent | the tangent line along which the peak was found normal to (normalized) | |
| prevPoint | the previous point along the tangent | |
| angleThreshold | the angle threshold to consider for valid peaks |
| void LaneDetector::mcvLines2Mat | ( | const vector< Line > * | lines, | |
| CvMat * | mat | |||
| ) |
This function converts an array of lines to a matrix (already allocated)
| lines | input vector of lines | |
| size | number of lines to convert |
| void LaneDetector::mcvLinesImIPM2Im | ( | vector< Line > & | lines, | |
| IPMInfo & | ipmInfo, | |||
| CameraInfo & | cameraInfo, | |||
| CvSize | imSize | |||
| ) |
This function converts lines from IPM image coordinates back to image coordinates
| lines | the input lines | |
| ipmInfo | the IPM info | |
| cameraInfo | the camera info | |
| imSize | the output image size (for clipping) |
| void LaneDetector::mcvLineXY2RTheta | ( | const Line & | line, | |
| float & | r, | |||
| float & | theta | |||
| ) |
This functions converts a line defined by its two end-points into its r and theta (origin is at top-left corner with x right and y down and theta measured positive clockwise(with y pointing down) -pi < theta < pi )
| line | input line | |
| r | the returned r (normal distance to the line from the origin) | |
| outLine | the output line |
This functions converts a line defined by its two end-points into its r and theta (origin is at top-left corner with x right and y down and theta measured positive clockwise<with y pointing down> -pi<theta<pi)
| line | input line | |
| r | the returned r (normal distance to the line from the origin) | |
| outLine | the output line |
| Spline LaneDetector::mcvLineXY2Spline | ( | const Line & | line, | |
| int | degree | |||
| ) |
This functions converts a line to a spline
| line | the line | |
| degree | the spline degree |
| void LaneDetector::mcvLoadImage | ( | const char * | filename, | |
| CvMat ** | clrImage, | |||
| CvMat ** | channelImage | |||
| ) |
This function reads in an image from file and returns the original color image and the first (red) channel scaled to [0 .. 1] with float type. images are allocated inside the function, so you will need to deallocate them
| clrImage | the raw input image | |
| channelImage | the first channel |
This function reads in an image from file and returns the original color image and the first (red) channel scaled to [0 .. 1] with float type. The images are allocated inside the function, so you will need to deallocate them
| filename | the input file name | |
| clrImage | the raw input image | |
| channelImage | the first channel |
| void LaneDetector::mcvLocalizePoints | ( | const CvMat * | im, | |
| const CvMat * | inPoints, | |||
| CvMat * | outPoints, | |||
| int | numLinePixels, | |||
| float | angleThreshold | |||
| ) |
This functions gives better localization of points along lines
| im | the input image | |
| inPoints | the input points Nx2 matrix of points | |
| outPoints | the output points Nx2 matrix of points | |
| numLinePixels | Number of pixels to go in normal direction for localization | |
| angleThreshold | Angle threshold used for localization (cosine, 1: most restrictive, 0: most liberal) |
i ||
| void LaneDetector::mcvMat2Lines | ( | const CvMat * | mat, | |
| vector< Line > * | lines | |||
| ) |
This function converts matrix into n array of lines
| mat | input matrix , it has 2x2*size where size is the number of lines, first row is x values (start.x, end.x) and second row is y-values | |
| lines | the rerurned vector of lines |
| void LaneDetector::mcvMatInt2Float | ( | const CvMat * | inMat, | |
| CvMat * | outMat | |||
| ) |
This function converts an INT mat into a FLOAT mat (already allocated)
| inMat | input INT matrix | |
| outMat | output FLOAT matrix |
| CvPoint2D32f LaneDetector::mcvMultiplyVector | ( | CvPoint2D32f | v, | |
| float | s | |||
| ) |
This functions multiplies a vector by a scalar
| v | the vector | |
| s | the scalar |
| CvPoint2D32f LaneDetector::mcvNormalizeVector | ( | float | x, | |
| float | y | |||
| ) |
This functions normalizes the given vector
| x | the x component | |
| y | the y component |
| CvPoint2D32f LaneDetector::mcvNormalizeVector | ( | const CvPoint & | v | ) |
This functions normalizes the given vector
| vector | the input vector to normalize |
| CvPoint2D32f LaneDetector::mcvNormalizeVector | ( | const CvPoint2D32f & | v | ) |
This functions normalizes the given vector
| vector | the input vector to normalize |
| void LaneDetector::mcvPointImIPM2World | ( | FLOAT_POINT2D * | point, | |
| const IPMInfo * | ipmInfo | |||
| ) |
Converts a point from IPM pixel coordinates into world coordinates
| point | in/out point | |
| ipmInfo | the ipm info from mcvGetIPM |
| void LaneDetector::mcvPostprocessLines | ( | const CvMat * | image, | |
| const CvMat * | clrImage, | |||
| const CvMat * | rawipm, | |||
| const CvMat * | fipm, | |||
| vector< Line > & | lines, | |||
| vector< float > & | lineScores, | |||
| vector< Spline > & | splines, | |||
| vector< float > & | splineScores, | |||
| LaneDetectorConf * | lineConf, | |||
| LineState * | state, | |||
| IPMInfo & | ipmInfo, | |||
| CameraInfo & | cameraInfo | |||
| ) |
This function postprocesses the detected lines/splines to better localize and extend them
| image | the input image | |
| clrImage | the inpout color image | |
| rawipm | the raw ipm image | |
| fipm | the filtered ipm iamge | |
| lines | a vector of lines | |
| lineScores | the line scores | |
| splines | a vector of returned splines | |
| splineScores | the spline scores | |
| lineConf | the conf structure | |
| state | the state for RANSAC splines | |
| ipmInfo | the ipmInfo structure | |
| cameraInfo | the camera info structure |
| void LaneDetector::mcvSampleWeighted | ( | const CvMat * | cumSum, | |
| int | numSamples, | |||
| CvMat * | randInd, | |||
| CvRNG * | rng | |||
| ) |
This function samples uniformly with weights
| cumSum | cumulative sum for normalized weights for the differnet samples (last is 1) | |
| numSamples | the number of samples | |
| randInd | a 1XnumSamples of int containing the indices | |
| rng | a pointer to a random number generator |
| void LaneDetector::mcvScaleCameraInfo | ( | CameraInfo * | cameraInfo, | |
| CvSize | size | |||
| ) |
Scales the cameraInfo according to the input image size
| cameraInfo | the input/return structure | |
| size | the input image size |
| void LaneDetector::mcvScaleMat | ( | const CvMat * | inMat, | |
| CvMat * | outMat | |||
| ) |
This function scales the input image to have values 0->1
| inImage | the input image | |
| outImage | hte output iamge |
| void LaneDetector::mcvSetMat | ( | CvMat * | inMat, | |
| CvRect | mask, | |||
| double | val | |||
| ) |
This function sets the matrix to a value except for the mask window passed in
| inMat | input matrix | |
| mask | the rectangle defining the mask: (xleft, ytop, width, height) | |
| val | the value to put |
| void LaneDetector::mcvSortPoints | ( | const CvMat * | inPoints, | |
| CvMat * | outPoints, | |||
| int | dim, | |||
| int | dir | |||
| ) |
This function sorts a set of points
| inPOints | Nx2 matrix of points [x,y] | |
| outPOints | Nx2 matrix of points [x,y] | |
| dim | the dimension to sort on (0: x, 1:y) | |
| dir | direction of sorting (0: ascending, 1:descending) |
This function fits a Bezier spline to the passed input points
| inPOints | Nx2 matrix of points [x,y] | |
| outPOints | Nx2 matrix of points [x,y] | |
| dim | the dimension to sort on (0: x, 1:y) | |
| dir | direction of sorting (0: ascending, 1:descending) |
| void LaneDetector::mcvSplinesImIPM2Im | ( | vector< Spline > & | splines, | |
| IPMInfo & | ipmInfo, | |||
| CameraInfo & | cameraInfo, | |||
| CvSize | imSize | |||
| ) |
This function converts splines from IPM image coordinates back to image coordinates
| splines | the input splines | |
| ipmInfo | the IPM info | |
| cameraInfo | the camera info | |
| imSize | the output image size (for clipping) |
| CvPoint2D32f LaneDetector::mcvSubtractVector | ( | const CvPoint2D32f & | v1, | |
| const CvPoint2D32f & | v2 | |||
| ) |
This functions computes difference between two vectors
| v1 | first vector | |
| v2 | second vector |
| void LaneDetector::mcvThresholdLower | ( | const CvMat * | inMat, | |
| CvMat * | outMat, | |||
| FLOAT | threshold | |||
| ) |
This function thresholds the image below a certain value to the threshold so: outMat(i,j) = inMat(i,j) if inMat(i,j)>=threshold = threshold otherwise
| inMat | input matrix | |
| outMat | output matrix | |
| threshold | threshold value |
| void LaneDetector::mcvTransformGround2Image | ( | const CvMat * | inPoints, | |
| CvMat * | outPoints, | |||
| const CameraInfo * | cameraInfo | |||
| ) |
Transforms points from the ground plane (z=-h) in the world frame into points on the image in image frame (uv-coordinates)
| inPoints | 2xN array of input points on the ground in world coordinates | |
| outPoints | 2xN output points in on the image in image coordinates | |
| cameraInfo | the camera parameters |
| void LaneDetector::mcvTransformImage2Ground | ( | const CvMat * | inPoints, | |
| CvMat * | outPoints, | |||
| const CameraInfo * | cameraInfo | |||
| ) |
Transforms points from the image frame (uv-coordinates) into the real world frame on the ground plane (z=-height)
| inPoints | input points in the image frame | |
| outPoints | output points in the world frame on the ground (z=-height) | |
| cemaraInfo | the input camera parameters |
Transforms points from the image frame (uv-coordinates) into the real world frame on the ground plane (z=-height)
| inPoints | input points in the image frame (2xN matrix) | |
| outPoints | output points in the world frame on the ground (z=-height) (2xN matrix with xw, yw and implicit z=-height) | |
| cemaraInfo | the input camera parameters |
| void LaneDetector::mcvTransformImIPM2Ground | ( | const CvMat * | inMat, | |
| CvMat * | outMat, | |||
| const IPMInfo * | ipmInfo | |||
| ) |
Converts from IPM pixel coordinates into world coordinates
| inMat | input matrix 2xN | |
| outMat | output matrix 2xN | |
| ipmInfo | the ipm info from mcvGetIPM |
| void LaneDetector::mcvTransformImIPM2Im | ( | const CvMat * | inMat, | |
| CvMat * | outMat, | |||
| const IPMInfo * | ipmInfo, | |||
| const CameraInfo * | cameraInfo | |||
| ) |
Converts from IPM pixel coordinates into Image coordinates
| inMat | input matrix 2xN | |
| outMat | output matrix 2xN | |
| ipmInfo | the ipm info from mcvGetIPM | |
| cameraInfo | the camera info |
| CvMat * LaneDetector::mcvVector2Mat | ( | const vector< T > & | vec | ) | [inline] |
This function creates a double matrix from an input vector
| vec | the input vector | |
| mat | the output matrix (column vector) |
| void LaneDetector::ProcessImage | ( | const char * | filename, | |
| CameraInfo & | cameraInfo, | |||
| LaneDetectorConf & | lanesConf, | |||
| LaneDetectorConf & | stoplinesConf, | |||
| gengetopt_args_info & | options, | |||
| ofstream * | outputFile = NULL, |
|||
| int | index = 0, |
|||
| clock_t * | elapsedTime = NULL | |||
| ) |
This function processes an input image and detects lanes/stoplines based on the passed in command line arguments
| filename | the input file name | |
| cameraInfo | the camera calibration info | |
| lanesConf | the lane detection settings | |
| stoplinesConf | the stop line detection settings | |
| options | the command line arguments | |
| outputFile | the output file stream to write output lanes to | |
| index | the image index (used for saving output files) | |
| elapsedTime | if NOT NULL, it is accumulated with clock ticks for the detection operation |
| bool LaneDetector::ReadLines | ( | const char * | filename, | |
| vector< string > * | lines | |||
| ) |
This function reads lines from the input file into a vector of strings
| filename | the input file name | |
| lines | the output vector of lines |
| void LaneDetector::SHOT_MAT_TYPE | ( | const CvMat * | pmat | ) |
| void LaneDetector::SHOW_IMAGE | ( | const IplImage * | pmat, | |
| char | str[] | |||
| ) |
| void LaneDetector::SHOW_IMAGE | ( | const CvMat * | pmat, | |
| const char | str[], | |||
| int | wait | |||
| ) |
| void LaneDetector::SHOW_LINE | ( | const Line | line, | |
| char | str[] | |||
| ) |
| void LaneDetector::SHOW_MAT | ( | const CvMat * | pmat, | |
| char | str[] | |||
| ) |
| void LaneDetector::SHOW_POINT | ( | const FLOAT_POINT2D | pt, | |
| char | str[] | |||
| ) |
| void LaneDetector::SHOW_RECT | ( | const CvRect | rect, | |
| char | str[] | |||
| ) |
| void LaneDetector::SHOW_SPLINE | ( | const Spline | spline, | |
| char | str[] | |||
| ) |
| int LaneDetector::DEBUG_LINES = 0 |
Definition at line 54 of file LaneDetector.cpp.