Skip to content

Commit 59905e4

Browse files
committed
Img processing: add lane detector
1 parent f3ad06d commit 59905e4

9 files changed

Lines changed: 738 additions & 5 deletions

File tree

img_processing/CMakeLists.txt

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,12 @@ if(SHOW_FRAMES)
1717
add_definitions(-DSHOW_FRAMES)
1818
endif()
1919

20+
# Check if LANE_DETECT flag is set
21+
option(LANE_DETECT "Enable lane detection" ON)
22+
if(LANE_DETECT)
23+
add_definitions(-DLANE_DETECT)
24+
endif()
25+
2026
# make the library with the src files
2127
file(GLOB SOURCES "src/*.cpp" "../logger/*.cpp" "tests/utils.cpp" "../communication/src/*.cpp" "../communication/sockets/*.cpp")
2228
add_library(ImageProcessingLib ${SOURCES})
@@ -26,7 +32,7 @@ add_library(CommunicationLib STATIC ../communication/src/communication.cpp ../co
2632

2733
configure_file( ${CMAKE_BINARY_DIR}/config.json COPYONLY)
2834
# create test executable
29-
add_executable(runTests tests/main.cpp tests/test_serialize.cpp tests/test_detector.cpp tests/test_dynamic_tracker.cpp tests/test_distance.cpp tests/test_manager.cpp tests/test_velocity.cpp)
35+
add_executable(runTests tests/main.cpp tests/test_serialize.cpp tests/test_detector.cpp tests/test_dynamic_tracker.cpp tests/test_distance.cpp tests/test_manager.cpp tests/test_velocity.cpp tests/test_lane_detector.cpp)
3036
target_link_libraries(runTests ImageProcessingLib ${OpenCV_LIBS} ${GTEST_LIBRARIES} pthread CommunicationLib)
3137

3238
#adding tests
Lines changed: 105 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
2+
#ifndef __LANE_DETECTION__
3+
#define __LANE_DETECTION__
4+
5+
#define _USE_MATH_DEFINES
6+
#include <cmath>
7+
#include "regression.h"
8+
#include "log_manager.h"
9+
#include <opencv2/highgui.hpp>
10+
#include <stdexcept>
11+
12+
#define CAR_IN_IMAGE 80
13+
14+
struct LaneDrawingInfo {
15+
int rightX1; //x bottom right
16+
int rightX2; //x top right
17+
int leftX1; //x bottom left
18+
int leftX2; //x top left
19+
int y1; //y bottom right & left
20+
int y2; //y top right & left
21+
};
22+
23+
class LaneDetector {
24+
public:
25+
void init();
26+
void manageLaneDetector(std::shared_ptr<cv::Mat> frame);
27+
void drawLanesOnImage(std::shared_ptr<cv::Mat> img);
28+
29+
private:
30+
std::shared_ptr<cv::Mat> image;
31+
bool first;
32+
bool withoutCar;
33+
int imgCols;
34+
int imgRows;
35+
LaneDrawingInfo drawingInfo;
36+
37+
/**
38+
* Returns true when the image is classified as daytime.
39+
* Note: this is based on the mean pixel value of an image and might not
40+
* always lead to accurate results.
41+
*/
42+
bool isDayTime();
43+
44+
/**
45+
* Filter source image so that only the white and yellow pixels remain.
46+
* A gray filter will also be added if the source image is classified as taken during the night.
47+
* One assumption for lane detection here is that lanes are either white or yellow.
48+
* @param isDayTime true if image is taken during the day, false if at night
49+
* @return Mat filtered image
50+
*/
51+
cv::Mat filterColors(bool isDayTime);
52+
53+
/**
54+
* Apply grayscale transform on image.
55+
* @return grayscale image
56+
*/
57+
cv::Mat applyGrayscale(cv::Mat source);
58+
59+
/**
60+
* Apply Gaussian blur to image.
61+
* @return blurred image
62+
*/
63+
cv::Mat applyGaussianBlur(cv::Mat source);
64+
65+
/**
66+
* Detect edges of image by applying canny edge detection.
67+
* @return image with detected edges
68+
*/
69+
cv::Mat applyCanny(cv::Mat source);
70+
71+
/**
72+
* Apply an image mask.
73+
* Only keep the part of the image defined by the
74+
* polygon formed from four points. The rest of the image is set to black.
75+
* @return Mat image with mask
76+
*/
77+
cv::Mat RegionOfInterest(cv::Mat source);
78+
79+
/**
80+
* Returns a vector with the detected hough lines.
81+
* @param canny image resulted from a canny transform
82+
* @param source image on which hough lines are drawn
83+
* @param drawHough draw detected lines on source image if true.
84+
* It will also show the image with de lines drawn on it, which is why
85+
* it is not recommended to pass in true when working with a video.
86+
* @return vector<Vec4i> contains hough lines.
87+
*/
88+
std::vector<cv::Vec4i> houghLines(cv::Mat canny, cv::Mat source,
89+
bool drawHough);
90+
91+
/**
92+
* Creates mask and blends it with source image so that the lanes
93+
* are drawn on the source image.
94+
* @param lines vector < vec4i > holding the lines
95+
* @return Mat image with lines drawn on it
96+
*/
97+
bool drawLanes(std::vector<cv::Vec4i> lines);
98+
99+
/**
100+
* Drawing the lane on the road only
101+
*/
102+
void cutCar();
103+
};
104+
105+
#endif /*__LANE_DETECTION__*/

img_processing/include/log_manager.h

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,8 @@ enum class ErrorType {
1212
FILE_ERROR,
1313
DETECTION_ERROR,
1414
TRACKING_ERROR,
15-
MODEL_ERROR
15+
MODEL_ERROR,
16+
SIZE_ERROR
1617
};
1718

1819
enum class InfoType {
@@ -29,7 +30,10 @@ enum class InfoType {
2930
MODE
3031
};
3132

32-
enum class DebugType { PRINT };
33+
enum class DebugType {
34+
PRINT,
35+
DRAW_PREV
36+
};
3337

3438
class LogManager {
3539
public:

img_processing/include/manager.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
#include "alerter.h"
66
#include "detector.h"
77
#include "distance.h"
8+
#include "lane-detector.h"
89
#include "dynamic_tracker.h"
910
#include "log_manager.h"
1011
#include "velocity.h"
@@ -30,6 +31,8 @@ class Manager {
3031
Velocity velocity;
3132
DynamicTracker dynamicTracker;
3233
Alerter alerter;
34+
LaneDetector laneDetector;
35+
int longTime;
3336
int iterationCnt;
3437
uint32_t destID;
3538
uint32_t processID;
Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
#ifndef __REGRESSION__
2+
#define __REGRESSION__
3+
4+
#include <vector>
5+
#include <numeric>
6+
#include <opencv2/opencv.hpp>
7+
8+
/**
9+
* @brief Multiplies two vectors and then calculates the sum of the multiplied values.
10+
* vector A and B must be the same size and their values must be of the same type.
11+
*
12+
* @param A vector<T>.
13+
* @param B vector<T>.
14+
* @return X sum of the multiplied values.
15+
*/
16+
template <typename T, typename X>
17+
X multiplyAndSum(std::vector<T> A, std::vector<T> B)
18+
{
19+
X sum;
20+
std::vector<T> temp;
21+
for (int i = 0; i < A.size(); i++) {
22+
temp.push_back(A[i] * B[i]);
23+
}
24+
sum = std::accumulate(temp.begin(), temp.end(), 0.0);
25+
26+
return sum;
27+
}
28+
29+
/**
30+
* @brief Calculates the coefficients (slope and intercept) of the best fitting line
31+
* given independent and dependent values. Vector A and B must be the same size
32+
* and their values must be of the same type.
33+
*
34+
* @param A vector<T> (independent values).
35+
* @param B vector<T> (dependent values).
36+
* @return vector<X> where first element is the slope (b1), second element is intercept (b0).
37+
*/
38+
template <typename T, typename X>
39+
std::vector<X> estimateCoefficients(std::vector<T> A, std::vector<T> B)
40+
{
41+
// Sample size
42+
int N = A.size();
43+
44+
// Calculate mean of X and Y
45+
X meanA = std::accumulate(A.begin(), A.end(), 0.0) / A.size();
46+
X meanB = std::accumulate(B.begin(), B.end(), 0.0) / B.size();
47+
48+
// Calculating cross-deviation and deviation about x
49+
X SSxy = multiplyAndSum<T, T>(A, B) - (N * meanA * meanB);
50+
X SSxx = multiplyAndSum<T, T>(A, A) - (N * meanA * meanA);
51+
52+
// Calculating regression coefficients
53+
X slopeB1 = SSxy / SSxx;
54+
X interceptB0 = meanB - (slopeB1 * meanA);
55+
56+
// Return vector, insert slope first and then intercept
57+
std::vector<X> coef;
58+
coef.push_back(slopeB1);
59+
coef.push_back(interceptB0);
60+
return coef;
61+
}
62+
63+
#endif /*__REGRESSION__*/

0 commit comments

Comments
 (0)