Commit 2ae5809357fc6f8b8aed74894bbac743c4de25ef
1 parent
f171c20a
添加road_seg算法
Showing
10 changed files
with
806 additions
and
2 deletions
bin/models/road_seg/tzroad_seg240108_310p.om
0 → 100755
No preview for this file type
build/src/Makefile
... | ... | @@ -20,6 +20,7 @@ INCLUDES = -I$(PROJ_ALL_PATH)/src/common \ |
20 | 20 | -I$(PROJ_ALL_PATH)/src/common/dvpp \ |
21 | 21 | -I$(PROJ_ALL_PATH)/src/common/cnn \ |
22 | 22 | -I$(PROJ_ALL_PATH)/src/common/cnn_cls \ |
23 | + -I$(PROJ_ALL_PATH)/src/common/road_cnn \ | |
23 | 24 | -I$(PROJ_ALL_PATH)/src/common/dvppx \ |
24 | 25 | -I$(PROJ_ALL_PATH)/src/common/model_process \ |
25 | 26 | -I$(CUR_PROJ_PATH)/../va \ |
... | ... | @@ -65,6 +66,7 @@ SRCS := $(wildcard $(CUR_PROJ_PATH)/*.cpp) \ |
65 | 66 | $(wildcard $(CUR_PROJ_PATH)/common/*.cpp) \ |
66 | 67 | $(wildcard $(CUR_PROJ_PATH)/common/dvpp/*.cpp) \ |
67 | 68 | $(wildcard $(CUR_PROJ_PATH)/common/cnn_cls/*.cpp) \ |
69 | + $(wildcard $(CUR_PROJ_PATH)/common/road_cnn/*.cpp) \ | |
68 | 70 | $(wildcard $(CUR_PROJ_PATH)/common/cnn/*.cpp) \ |
69 | 71 | $(wildcard $(CUR_PROJ_PATH)/common/dvppx/*.cpp) \ |
70 | 72 | $(wildcard $(CUR_PROJ_PATH)/common/model_process/*.cpp) \ |
... | ... | @@ -95,6 +97,9 @@ $(TARGET):$(OBJS) |
95 | 97 | %.o:$(CUR_PROJ_PATH)/common/cnn_cls/%.cpp |
96 | 98 | $(XX) $(CXXFLAGS) -c $< |
97 | 99 | |
100 | +%.o:$(CUR_PROJ_PATH)/common/road_cnn/%.cpp | |
101 | + $(XX) $(CXXFLAGS) -c $< | |
102 | + | |
98 | 103 | %.o:$(CUR_PROJ_PATH)/common/dvppx/%.cpp |
99 | 104 | $(XX) $(CXXFLAGS) -c $< |
100 | 105 | ... | ... |
src/PicAnalysis.cpp
... | ... | @@ -50,7 +50,12 @@ int PicAnalysis::init(int dev_id) { |
50 | 50 | // return -1; |
51 | 51 | // } |
52 | 52 | |
53 | - ret = m_motor_phone_algorithm.init(dev_id); | |
53 | + // ret = m_motor_phone_algorithm.init(dev_id); | |
54 | + // if(0 != ret){ | |
55 | + // return -1; | |
56 | + // } | |
57 | + | |
58 | + ret = m_road_seg_algorithm.init(dev_id); | |
54 | 59 | if(0 != ret){ |
55 | 60 | return -1; |
56 | 61 | } |
... | ... | @@ -117,7 +122,9 @@ int PicAnalysis::analysis_sync(vector<string> vec_file_path){ |
117 | 122 | |
118 | 123 | // m_motor_rainshed_algorithm.detect(vec_img); |
119 | 124 | |
120 | - m_motor_phone_algorithm.detect(vec_img); | |
125 | + // m_motor_phone_algorithm.detect(vec_img); | |
126 | + | |
127 | + m_road_seg_algorithm.detect(vec_img); | |
121 | 128 | |
122 | 129 | LOG_INFO("analysis_sync finished!"); |
123 | 130 | ... | ... |
src/PicAnalysis.h
... | ... | @@ -6,6 +6,7 @@ |
6 | 6 | #include "./ai_engine_module/HumanCarAnalysis.h" |
7 | 7 | #include "./ai_engine_module/MotorRainshedAnalysis.h" |
8 | 8 | #include "./ai_engine_module/MotorPhoneAnalysis.h" |
9 | +#include "./ai_engine_module/RoadSegAnalysis.h" | |
9 | 10 | |
10 | 11 | using namespace std; |
11 | 12 | |
... | ... | @@ -35,6 +36,7 @@ private: |
35 | 36 | HumanCarAnalysis m_human_car_algorithm; |
36 | 37 | MotorRainshedAnalysis m_motor_rainshed_algorithm; |
37 | 38 | MotorPhoneAnalysis m_motor_phone_algorithm; |
39 | + RoadSegAnalysis m_road_seg_algorithm; | |
38 | 40 | }; |
39 | 41 | |
40 | 42 | ... | ... |
src/ai_engine_module/RoadSegAnalysis.cpp
0 → 100644
1 | +#include "RoadSegAnalysis.h" | |
2 | +#include "road_seg.h" | |
3 | + | |
4 | +RoadSegAnalysis::RoadSegAnalysis(/* args */) | |
5 | +{ | |
6 | +} | |
7 | + | |
8 | +RoadSegAnalysis::~RoadSegAnalysis() | |
9 | +{ | |
10 | + release(); | |
11 | +} | |
12 | + | |
13 | +int RoadSegAnalysis::init(int devId){ | |
14 | + ACL_CALL(aclrtCreateContext(&ctx, devId), SY_SUCCESS, SY_FAILED); | |
15 | + | |
16 | + rs_param param; | |
17 | + param.modelNames = "./models/road_seg/tzroad_seg240108_310p.om"; | |
18 | + param.thresld = 0.25; | |
19 | + param.devId = devId; | |
20 | + | |
21 | + cout << "rs_init start " << endl; | |
22 | + int ret = rs_init(&m_handle, param); | |
23 | + if (ret != 0) { | |
24 | + return -1; | |
25 | + } | |
26 | + | |
27 | + cout << "rs_init success " << endl; | |
28 | + | |
29 | + return SY_SUCCESS; | |
30 | +} | |
31 | + | |
32 | +int RoadSegAnalysis::detect(vector<sy_img> vec_img){ | |
33 | + | |
34 | + ACL_CALL(aclrtSetCurrentContext(ctx), SY_SUCCESS, SY_FAILED); | |
35 | + | |
36 | + const int batchsize = vec_img.size(); | |
37 | + rs_result results[batchsize]; | |
38 | + const int fea_size = 360*640; | |
39 | + for (int b = 0; b < batchsize; b++) { | |
40 | + results[b].seg_array = new unsigned char[fea_size]; | |
41 | + results[b].direct_seg = new unsigned char[fea_size]; | |
42 | + } | |
43 | + | |
44 | + int ret = SY_FAILED; | |
45 | + | |
46 | + do | |
47 | + { | |
48 | + ret = rs_batch(m_handle, vec_img.data(), batchsize, results); | |
49 | + if (SY_SUCCESS != ret) { | |
50 | + printf("mrc_batch failed!"); | |
51 | + break; | |
52 | + } | |
53 | + | |
54 | + // todo 结果处理 | |
55 | + } while (0); | |
56 | + | |
57 | + for (int b = 0; b < batchsize; b++) { | |
58 | + delete[] results[b].seg_array; results[b].seg_array = NULL; | |
59 | + delete[] results[b].direct_seg; results[b].direct_seg = NULL; | |
60 | + } | |
61 | + | |
62 | + return ret; | |
63 | +} | |
64 | + | |
65 | +int RoadSegAnalysis::release() { | |
66 | + | |
67 | + ACL_CALL(aclrtSetCurrentContext(ctx), SY_SUCCESS, SY_FAILED); | |
68 | + | |
69 | + if (m_handle) { | |
70 | + rs_release(&m_handle); | |
71 | + } | |
72 | + | |
73 | + if(ctx){ | |
74 | + aclrtDestroyContext(ctx); | |
75 | + ctx = nullptr; | |
76 | + } | |
77 | + | |
78 | + return SY_SUCCESS; | |
79 | +} | |
0 | 80 | \ No newline at end of file | ... | ... |
src/ai_engine_module/RoadSegAnalysis.h
0 → 100644
1 | +#include "include.h" | |
2 | + | |
3 | +class RoadSegAnalysis | |
4 | +{ | |
5 | +public: | |
6 | + RoadSegAnalysis(/* args */); | |
7 | + ~RoadSegAnalysis(); | |
8 | + | |
9 | + int init(int devId); | |
10 | + | |
11 | + int detect(vector<sy_img> vec_img); | |
12 | + | |
13 | +private: | |
14 | + int release(); | |
15 | + | |
16 | +private: | |
17 | + void* m_handle{nullptr}; | |
18 | + aclrtContext ctx{nullptr}; | |
19 | +}; | |
20 | + | ... | ... |
src/ai_engine_module/road_seg.cpp
0 → 100755
1 | +#include "road_seg.h" | |
2 | +#include "sy_errorinfo.h" | |
3 | +#include "road_extractor.h" | |
4 | +#include "dvpp_processx.h" | |
5 | +#include <time.h> | |
6 | +#include <sys/time.h> | |
7 | +#include "stream_data.h" | |
8 | +#include <algorithm> | |
9 | +#include <map> | |
10 | +#include <cstring> | |
11 | +#include <cmath> | |
12 | + | |
13 | + | |
14 | +using namespace atlas_utils; | |
15 | +using namespace std; | |
16 | + | |
17 | +struct Resource { | |
18 | + aclrtContext ctx; | |
19 | + aclrtStream stream; | |
20 | +}; | |
21 | + | |
22 | +typedef struct Tools { | |
23 | + Resource src; | |
24 | + ROADExtract* roadsegExtract; | |
25 | + DvppProcessx* dvpp; | |
26 | + | |
27 | +}Tools; | |
28 | + | |
29 | + | |
30 | +int rs_init(void **handle, rs_param param){ | |
31 | + | |
32 | + int ret = SY_SUCCESS; | |
33 | + Tools* tools = new Tools; | |
34 | + // init resource | |
35 | + ACL_CALL(aclrtCreateStream(&tools->src.stream), ACL_SUCCESS, SY_FAILED); | |
36 | + | |
37 | + // head_shoulder detection init | |
38 | + tools->roadsegExtract = new ROADExtract(); | |
39 | + tools->roadsegExtract->config.confThr = param.thresld; | |
40 | + | |
41 | + ret = tools->roadsegExtract->Init(param.modelNames); | |
42 | + if (ret != SY_SUCCESS) { | |
43 | + delete tools->roadsegExtract; | |
44 | + tools->roadsegExtract = nullptr; | |
45 | + return SY_FAILED; | |
46 | + } | |
47 | + | |
48 | + tools->dvpp = new DvppProcessx(); | |
49 | + tools->dvpp->InitResource(tools->src.stream); | |
50 | + | |
51 | + *handle = tools; | |
52 | + | |
53 | + return SY_SUCCESS; | |
54 | +} | |
55 | + | |
56 | +namespace road_seg_7cls | |
57 | +{ | |
58 | + int lane_cls_classes = 6; //5 + 1 | |
59 | + int road_seg_classes = 9; //8类别+背景 | |
60 | + int direct_seg_classes = 5; //4类别+背景 | |
61 | + std::vector<float> lane_softmax(const std::vector<float>& x) { | |
62 | + std::vector<float> result(x.size()); | |
63 | + // 实现softmax逻辑 | |
64 | + float max_val = *std::max_element(x.begin(), x.end()); | |
65 | + float sum = 0.0; | |
66 | + for (size_t i = 0; i < x.size(); i++) { | |
67 | + result[i] = std::exp(x[i] - max_val); | |
68 | + sum += result[i]; | |
69 | + } | |
70 | + for (size_t i = 0; i < x.size(); i++) { | |
71 | + result[i] /= sum; | |
72 | + } | |
73 | + | |
74 | + return result; | |
75 | + } | |
76 | + | |
77 | + std::vector<float> lane_linspace(float start, float end, int n) { | |
78 | + std::vector<float> result; | |
79 | + float step = (end - start) / (n - 1); | |
80 | + for (int i = 0; i < n; i++) { | |
81 | + result.push_back(start + step * i); | |
82 | + } | |
83 | + return result; | |
84 | + } | |
85 | + | |
86 | + bool Lane_IOU(const std::vector<float>& parent_box, const std::vector<float>& compared_box, int threshold) { | |
87 | + // 实现Lane_IOU逻辑 | |
88 | + int y = lane_cls_classes, length = y + 2, offset_start = y + 3; | |
89 | + | |
90 | + int n_offsets = 72; | |
91 | + int n_strips = n_offsets - 1; | |
92 | + | |
93 | + int start_a = static_cast<int>((parent_box[y] * n_strips) + 0.5); | |
94 | + int start_b = static_cast<int>((compared_box[y] * n_strips) + 0.5); | |
95 | + int start = std::max(start_a, start_b); | |
96 | + int end_a = start_a + static_cast<int>(parent_box[length]) - 1 + 0.5 - ((parent_box[length] - 1 < 0) ? 1 : 0); | |
97 | + int end_b = start_b + static_cast<int>(compared_box[length]) - 1 + 0.5 - ((compared_box[length] - 1 < 0) ? 1 : 0); | |
98 | + int end = std::min(std::min(end_a, end_b), n_strips); | |
99 | + if (end - start < 0) { | |
100 | + return false; | |
101 | + } | |
102 | + int dist = 0; | |
103 | + for (int i = offset_start + start; i < offset_start + end; i++) { | |
104 | + if (i > (offset_start + end)) { | |
105 | + break; | |
106 | + } | |
107 | + if (parent_box[i] < compared_box[i]) { | |
108 | + dist += (compared_box[i] - parent_box[i]); | |
109 | + } else { | |
110 | + dist += (parent_box[i] - compared_box[i]); | |
111 | + } | |
112 | + } | |
113 | + return dist < (threshold * (end - start + 1)); | |
114 | + } | |
115 | + | |
116 | + void Lane_nms(const std::vector<std::vector<float>>& proposals, std::vector<size_t> &keep_index, size_t &num_to_keep, const std::vector<float>& scores, int overlap = 50, int top_k = 4) { | |
117 | + // 实现Lane_nms逻辑 | |
118 | + /*std::vector<float> sorted_score = scores; | |
119 | + std::sort(sorted_score.begin(), sorted_score.end(), std::greater<float>());*/ | |
120 | + std::vector<int> indices(scores.size()); | |
121 | + for (size_t i = 0; i < indices.size(); i++) { | |
122 | + indices[i] = i; | |
123 | + } | |
124 | + std::sort(indices.begin(), indices.end(), [&](int a, int b) { return scores[a] > scores[b]; }); | |
125 | + | |
126 | + std::vector<int> r_filters(scores.size(), 0); | |
127 | + | |
128 | + for (size_t i = 0; i < indices.size(); i++) { | |
129 | + int indice = indices[i]; | |
130 | + if (r_filters[i] == 1) { // continue if this proposal is filtered by nms before | |
131 | + continue; | |
132 | + } | |
133 | + keep_index.push_back(indice); | |
134 | + if (keep_index.size() > static_cast<size_t>(top_k)) { // break if more than top_k | |
135 | + break; | |
136 | + } | |
137 | + if (i == indices.size() - 1) { // break if indice is the last one | |
138 | + break; | |
139 | + } | |
140 | + std::vector<int> sub_indices(indices.begin() + i + 1, indices.end()); | |
141 | + for (size_t sub_i = 0; sub_i < sub_indices.size(); sub_i++) { | |
142 | + int sub_indice = sub_indices[sub_i]; | |
143 | + bool r_filter = Lane_IOU(proposals[indice], proposals[sub_indice], overlap); | |
144 | + if (r_filter) { | |
145 | + r_filters[i + 1 + sub_i] = 1; | |
146 | + } | |
147 | + } | |
148 | + } | |
149 | + | |
150 | + num_to_keep = static_cast<int>(keep_index.size()); | |
151 | + } | |
152 | + | |
153 | + | |
154 | + int predictions_to_pred(const std::vector<std::vector<float>>& predictions, rs_lane* reg_array, int n_strips, int n_offsets) { | |
155 | + std::vector<float> prior_ys = lane_linspace(1.0, 0.0, n_offsets); | |
156 | + int lane_count = 0; | |
157 | + int start_x = lane_cls_classes + 1, start_y = lane_cls_classes, offset_start = lane_cls_classes + 4, length_ = lane_cls_classes + 3; | |
158 | + for (const auto& lane : predictions) { | |
159 | + std::vector<float> lane_xs(lane.begin() + offset_start, lane.end()); // normalized value | |
160 | + int start = std::min(std::max(0, static_cast<int>(std::round(lane[start_y] * n_strips))), n_strips); | |
161 | + int length = static_cast<int>(std::round(lane[length_])); | |
162 | + int end = start + length - 1; | |
163 | + end = std::min(end, static_cast<int>(prior_ys.size()) - 1); | |
164 | + /* | |
165 | + std::vector<bool> mask(prior_ys.size(), false); | |
166 | + for (int i = 0; i < start; i++) { | |
167 | + if (lane_xs[i] >= 0.0 && lane_xs[i] <= 1.0) { | |
168 | + mask[i] = true; | |
169 | + } | |
170 | + } | |
171 | + for (int i = end + 1; i < static_cast<int>(prior_ys.size()); i++) { | |
172 | + if (lane_xs[i] >= 0.0 && lane_xs[i] <= 1.0) { | |
173 | + mask[i] = true; | |
174 | + } | |
175 | + }*/ | |
176 | + | |
177 | + std::fill(lane_xs.begin() + end + 1, lane_xs.end(), -2); | |
178 | + std::fill(lane_xs.begin(), lane_xs.begin() + start, -2); | |
179 | + | |
180 | + std::vector<float> lane_ys; | |
181 | + for (size_t i = 0; i < prior_ys.size(); i++) { | |
182 | + // if (!mask[i]) { | |
183 | + if (lane_xs[i] >= 0) { | |
184 | + lane_ys.push_back(prior_ys[i]); | |
185 | + } | |
186 | + } | |
187 | + | |
188 | + std::vector<float> lane_xs_new; | |
189 | + for (size_t i = 0; i < prior_ys.size(); i++) { | |
190 | + // if (!mask[i]) { | |
191 | + if (lane_xs[i] >= 0) { | |
192 | + lane_xs_new.push_back(lane_xs[i]); | |
193 | + } | |
194 | + } | |
195 | + | |
196 | + | |
197 | + if (lane_xs_new.empty()) { | |
198 | + continue; | |
199 | + } | |
200 | + | |
201 | + int lane_xs_new_size = lane_xs_new.size(); | |
202 | + // if (lane_xs_new_size <= 1) { | |
203 | + // continue; | |
204 | + // } | |
205 | + | |
206 | + if (lane_xs_new_size > 180) { | |
207 | + lane_xs_new_size = 180; | |
208 | + } | |
209 | + | |
210 | + int count = 0; | |
211 | + #if 1 | |
212 | + for (size_t i = 0; i < lane_xs_new_size; i++) { | |
213 | + // float lane_x = lane_xs_new[i], lane_y = lane_ys[i]; | |
214 | + float lane_x = lane_xs_new[i] * 640; | |
215 | + float lane_y = lane_ys[i] * 360; | |
216 | + reg_array[lane_count].points[count].x_ = lane_x; | |
217 | + reg_array[lane_count].points[count].y_ = lane_y; | |
218 | + // printf("lane_x:%f lane_y:%f %d %d\n", lane_x, lane_y, reg_array[lane_count].points[count].x_, reg_array[lane_count].points[count].y_); | |
219 | + count ++; | |
220 | + } | |
221 | + #endif | |
222 | + | |
223 | + reg_array[lane_count].start_x = lane[start_x]* 640; | |
224 | + reg_array[lane_count].start_y = lane[start_y]* 360; | |
225 | + | |
226 | + | |
227 | + std::vector<float> lane_info(lane.begin()+1, lane.begin()+lane_cls_classes); // 去除背景类别 | |
228 | + std::vector<float> softmax_res = lane_softmax(lane_info); | |
229 | + reg_array[lane_count].cls = std::distance(softmax_res.begin(),std::max_element(softmax_res.begin(),softmax_res.end())) + 1; | |
230 | + reg_array[lane_count].conf = *(std::max_element(softmax_res.begin(),softmax_res.end())); | |
231 | + reg_array[lane_count].num_points = count; | |
232 | + lane_count ++; | |
233 | + } | |
234 | + return lane_count; | |
235 | + } | |
236 | + | |
237 | + // 统一求nms | |
238 | + int get_lanes(const vector<float> output, rs_lane* reg_array, float conf_threshold, int nms_thres, int max_lanes) { | |
239 | + | |
240 | + int stride1 = 192, stride2 = 82, num_points = 72, input_width = 640, input_height = 360; | |
241 | + int theta = lane_cls_classes + 2, length = lane_cls_classes + 3; | |
242 | + int n_strips = num_points - 1, n_offsets = num_points; | |
243 | + std::vector<std::vector<float>> predictions, nms_predictions; | |
244 | + std::vector<float> scores; | |
245 | + for (int i = 0; i < stride1; i++) { | |
246 | + std::vector<float> pred_score(output.begin() + i*stride2, output.begin() + i*stride2+lane_cls_classes); // 存储类别得分 | |
247 | + std::vector<float> softmax_res = lane_softmax(pred_score); | |
248 | + std::vector<float> selected_scores(softmax_res.begin()+1, softmax_res.begin()+lane_cls_classes); // 选择目标类别的概率值,去除背景类别 | |
249 | + float max_score = *std::max_element(selected_scores.begin(), selected_scores.end()); | |
250 | + if (max_score >= conf_threshold) { | |
251 | + std::vector<float> pred(output.begin() + i*stride2, output.begin() + (i+1)*stride2); | |
252 | + nms_predictions.push_back(pred); | |
253 | + predictions.push_back(pred); | |
254 | + scores.push_back(max_score); | |
255 | + } | |
256 | + } | |
257 | + | |
258 | + for (auto& row : nms_predictions) { | |
259 | + row[theta] *= n_strips; | |
260 | + for (size_t i = length; i < row.size(); i++) { | |
261 | + row[i] *= (input_width - 1); | |
262 | + } | |
263 | + } | |
264 | + | |
265 | + std::vector<size_t> keep; | |
266 | + size_t num_to_keep; | |
267 | + Lane_nms(nms_predictions, keep, num_to_keep, scores, nms_thres, max_lanes); | |
268 | + keep.resize(num_to_keep); | |
269 | + | |
270 | + std::vector<std::vector<float>> final_predictions; | |
271 | + for (auto& index : keep) { | |
272 | + predictions[index][length] = round(predictions[index][length] * n_strips); | |
273 | + final_predictions.push_back(predictions[index]); | |
274 | + } | |
275 | + | |
276 | + int lane_count = predictions_to_pred(final_predictions, reg_array, n_strips, n_offsets); | |
277 | + return lane_count; | |
278 | + } | |
279 | + | |
280 | + // 对每个类别分别求nms | |
281 | + int get_lanesV2(const vector<float> output, rs_lane* reg_array, float conf_threshold, int nms_thres, int max_lanes) { | |
282 | + | |
283 | + int stride1 = 192, stride2 = 82, num_points = 72, input_width = 640, input_height = 360; | |
284 | + int theta = lane_cls_classes + 2, length = lane_cls_classes + 3; | |
285 | + int n_strips = num_points - 1, n_offsets = num_points; | |
286 | + | |
287 | + std::vector<std::vector<float>> final_predictions; | |
288 | + for (int cls = 0; cls < lane_cls_classes; cls++) { | |
289 | + std::vector<std::vector<float>> predictions, nms_predictions; | |
290 | + std::vector<float> scores; | |
291 | + for (int i = 0; i < stride1; i++) { | |
292 | + std::vector<float> pred_score(output.begin() + i*stride2, output.begin() + i*stride2+lane_cls_classes); // 存储类别得分 | |
293 | + std::vector<float> softmax_res = lane_softmax(pred_score); | |
294 | + std::vector<float> selected_scores(softmax_res.begin()+1, softmax_res.begin()+lane_cls_classes); // 选择目标类别的概率值,去除背景类别 | |
295 | + | |
296 | + auto iter = std::max_element(selected_scores.begin(), selected_scores.end()); | |
297 | + int indice = std::distance(selected_scores.begin(), iter); | |
298 | + float max_score = *iter; | |
299 | + if (indice == cls && max_score >= conf_threshold) { | |
300 | + std::vector<float> pred(output.begin() + i*stride2, output.begin() + (i+1)*stride2); | |
301 | + nms_predictions.push_back(pred); | |
302 | + predictions.push_back(pred); | |
303 | + scores.push_back(max_score); | |
304 | + } | |
305 | + } | |
306 | + | |
307 | + for (auto& row : nms_predictions) { | |
308 | + row[theta] *= n_strips; | |
309 | + for (size_t i = length; i < row.size(); i++) { | |
310 | + row[i] *= (input_width - 1); | |
311 | + } | |
312 | + } | |
313 | + | |
314 | + std::vector<size_t> keep; | |
315 | + size_t num_to_keep; | |
316 | + Lane_nms(nms_predictions, keep, num_to_keep, scores, nms_thres, max_lanes); | |
317 | + keep.resize(num_to_keep); | |
318 | + | |
319 | + | |
320 | + for (auto& index : keep) { | |
321 | + predictions[index][length] = round(predictions[index][length] * n_strips); | |
322 | + final_predictions.push_back(predictions[index]); | |
323 | + } | |
324 | + } | |
325 | + | |
326 | + int lane_count = predictions_to_pred(final_predictions, reg_array, n_strips, n_offsets); | |
327 | + return lane_count; | |
328 | + } | |
329 | + | |
330 | + | |
331 | + // 获取道路分割结果中最大值的索引(类别) | |
332 | + // int road_seg_show(const float* inference_features, uint8_t *road_seg) { | |
333 | + int road_seg_show(const vector<float> inference_features, uint8_t *road_seg, int seg_num_cls) { | |
334 | + int h = 360, w = 640; | |
335 | + int step_size = h*w; | |
336 | + for (int i = 0; i < h; i++) { | |
337 | + for (int j = 0; j < w; j++) { | |
338 | + float max_score = 0; int max_cls = 0; | |
339 | + for (int k = 0; k < seg_num_cls; k++) { | |
340 | + int cur_steps = i*w+j+k*step_size; | |
341 | + if (inference_features[cur_steps] > max_score) { | |
342 | + max_score = inference_features[cur_steps]; | |
343 | + max_cls = k; | |
344 | + } | |
345 | + } | |
346 | + // if (max_cls == 5 || max_cls == 6) max_cls = 0; // 将分割的车道线变成背景,防止混淆================ | |
347 | + road_seg[i*w+j] = max_cls; | |
348 | + } | |
349 | + } | |
350 | + | |
351 | + return 0; | |
352 | + } | |
353 | +} | |
354 | + | |
355 | +int rs_process(void *handle, sy_img img_data, rs_result result) | |
356 | +{ | |
357 | + return rs_batch(handle, &img_data, 1, &result); | |
358 | +} | |
359 | + | |
360 | +int rs_batch(void * handle, sy_img *image_data_array, int batchsize, rs_result *result){ | |
361 | + Tools* tools = (Tools*) handle; | |
362 | + | |
363 | + int inputW = tools->roadsegExtract->GetInputWidth(); | |
364 | + int inputH = tools->roadsegExtract->GetInputHeight(); | |
365 | + | |
366 | + //printf("debug inputw:%d,inputh:%d\n",inputW,inputH); | |
367 | + | |
368 | + for (int b = 0; b < batchsize; b++) { | |
369 | + if (image_data_array[b].data_ == NULL || image_data_array[b].w_ == 0 || image_data_array[b].h_ == 0) { | |
370 | + ERROR_LOG(" RoadSegExtract get null input ptr!"); | |
371 | + return SY_FAILED; | |
372 | + } | |
373 | + | |
374 | + ImageData resizeImg, src; | |
375 | + // Utils::CopysyImageDataToDvpp(src, image_data_array[b]); | |
376 | + ACL_CALL(Utils::CopysyImageDataToDvppV2(src, image_data_array[b]), SY_SUCCESS, SY_FAILED); | |
377 | + ACL_CALL(tools->dvpp->CropAndPadding(resizeImg, src, inputW, inputH), SY_SUCCESS, SY_FAILED); | |
378 | + // forward | |
379 | + // double t1, t2; | |
380 | + // t1 = msecond(); | |
381 | + int ret = tools->roadsegExtract->Inference(resizeImg); | |
382 | + if (ret != SY_SUCCESS) { | |
383 | + return SY_MODEL_FORWARD_ERROR; | |
384 | + } | |
385 | + // t2 = msecond(); | |
386 | + // printf("debug infer time: %.2f\n", t2 - t1); | |
387 | + | |
388 | + vector<float> detRes; | |
389 | + ret = tools->roadsegExtract->PostProcess(detRes); | |
390 | + if (ret != SY_SUCCESS) { | |
391 | + return SY_MODEL_GETRESULT_ERROR; | |
392 | + } | |
393 | + | |
394 | + int lane_length = 192 * 82; | |
395 | + int roadseg_length = 360 * 640 * road_seg_7cls::road_seg_classes; | |
396 | + std::vector<float> clane_detection(detRes.begin(), detRes.begin() + lane_length); | |
397 | + std::vector<float> croad_segmentation(detRes.begin() + lane_length, detRes.begin() + lane_length + roadseg_length); | |
398 | + std::vector<float> cdirect_segmentation(detRes.begin() + lane_length + roadseg_length, detRes.end()); | |
399 | + | |
400 | + int res = road_seg_7cls::road_seg_show(croad_segmentation, result[b].seg_array, road_seg_7cls::road_seg_classes); | |
401 | + res = road_seg_7cls::road_seg_show(cdirect_segmentation, result[b].direct_seg, road_seg_7cls::direct_seg_classes); | |
402 | + float conf_threshold = 0.4; | |
403 | + int nms_thres = 50, max_lanes = 21; | |
404 | + int lane_count = road_seg_7cls::get_lanesV2(clane_detection, result[b].reg_array, conf_threshold, nms_thres, max_lanes); | |
405 | + result[b].lane_count = lane_count; | |
406 | + | |
407 | + vector<float>().swap(detRes); | |
408 | + vector<float>().swap(clane_detection); | |
409 | + vector<float>().swap(croad_segmentation); | |
410 | + vector<float>().swap(cdirect_segmentation); | |
411 | + } | |
412 | + | |
413 | + return SY_SUCCESS; | |
414 | +} | |
415 | + | |
416 | +void rs_release(void **handle) { | |
417 | + if (*handle) { | |
418 | + Tools* tools = (Tools*) *handle; | |
419 | + if (tools->roadsegExtract) { | |
420 | + delete tools->roadsegExtract; | |
421 | + tools->roadsegExtract = nullptr; | |
422 | + } | |
423 | + if (tools->dvpp) { | |
424 | + delete tools->dvpp; | |
425 | + tools->dvpp = nullptr; | |
426 | + } | |
427 | + // aclFinalize(); | |
428 | + delete tools; | |
429 | + tools = NULL; | |
430 | + } | |
431 | +} | |
432 | + | |
433 | +const char * rs_get_version() { | |
434 | + return "road_seg_vdec_arm_v310p_0.0.2.20240110_without_timelimit"; | |
435 | +} | |
0 | 436 | \ No newline at end of file | ... | ... |
src/ai_engine_module/road_seg.h
0 → 100755
1 | +/************************************************************************* | |
2 | +* Version: road_seg_v0.0.0.20230313 | |
3 | +* CopyRight : 中国科学院自动化所模式识别实验室图像视频组 | |
4 | +* UpdateDate: | |
5 | +* Content : 道路分割 | |
6 | +*************************************************************************/ | |
7 | +#ifndef ROADSEG_H_ | |
8 | +#define ROADSEG_H_ | |
9 | + | |
10 | +#if _MSC_VER | |
11 | +#ifdef ROADSEG_EXPORTS | |
12 | +#define ROADSEG_API __declspec(dllexport) | |
13 | +#else | |
14 | +#define ROADSEG_API __declspec(dllimport) | |
15 | +#endif | |
16 | +#else | |
17 | +#define ROADSEG_API __attribute__ ((visibility ("default"))) | |
18 | +#endif | |
19 | + | |
20 | +#include "sy_common.h" | |
21 | + | |
22 | +#ifdef __cplusplus | |
23 | +extern "C" | |
24 | +{ | |
25 | +#endif | |
26 | + | |
27 | +#ifndef __RS_LANE__ | |
28 | +#define __RS_LANE__ | |
29 | +typedef struct rs_lane { | |
30 | + sy_point points[180]; // 车道线上的点坐标数组 | |
31 | + int num_points; // 车道线上点的数量 | |
32 | + float start_x; // 起始点x坐标 | |
33 | + float start_y; // 起始点y坐标 | |
34 | + float cls; // 车道线类别 1-实线 2-虚线 | |
35 | + float conf; // 车道线置信度 | |
36 | +}rs_lane; | |
37 | +#endif | |
38 | + | |
39 | +#ifndef __rs_RESULT__ | |
40 | +#define __rs_RESULT__ | |
41 | + typedef struct rs_result | |
42 | + { | |
43 | + rs_lane reg_array[20]; | |
44 | + int lane_count; | |
45 | + unsigned char *seg_array; | |
46 | + unsigned char *direct_seg; | |
47 | + }rs_result; | |
48 | +#endif | |
49 | + | |
50 | +#ifndef __rs_PARAM__ | |
51 | +#define __rs_PARAM__ | |
52 | + typedef struct rs_param | |
53 | + { | |
54 | + int devId; //运行卡号 | |
55 | + char* modelNames; | |
56 | + float thresld; //检测阈值 默认为0.3 | |
57 | + }rs_param; | |
58 | +#endif | |
59 | + | |
60 | + /************************************************************************* | |
61 | + * FUNCTION: rs_init | |
62 | + * PURPOSE: 载入模型 | |
63 | + * PARAM: | |
64 | + [in] handle - 句柄 | |
65 | + [in] params - 参数 | |
66 | + * RETURN: 成功(0)或者错误代码 | |
67 | + * NOTES: | |
68 | + *************************************************************************/ | |
69 | + ROADSEG_API int rs_init(void ** handle, rs_param param); | |
70 | + | |
71 | + /************************************************************************* | |
72 | + * FUNCTION: rs_process | |
73 | + * PURPOSE: 车颜色识别 | |
74 | + * PARAM: | |
75 | + [in] handle - 检测句柄 | |
76 | + [in] img_data - 图像数据 | |
77 | + [in] result - 结果 内存在外部申请 | |
78 | + * RETURN: 成功(0) 或 错误代码(< 0) | |
79 | + * NOTES: | |
80 | + *************************************************************************/ | |
81 | + ROADSEG_API int rs_process(void *handle, sy_img img_data, rs_result result); | |
82 | + | |
83 | + /************************************************************************* | |
84 | + * FUNCTION: rs_batch | |
85 | + * PURPOSE: 车颜色识别 batch | |
86 | + * PARAM: | |
87 | + [in] handle - 检测句柄 | |
88 | + [in] img_data_array - 图像数据 | |
89 | + [in] batch_size - 图像数目 | |
90 | + [in] result - 结果 内存在外部申请 | |
91 | + * RETURN: 成功(0) 或 错误代码(< 0) | |
92 | + * NOTES: | |
93 | + *************************************************************************/ | |
94 | + ROADSEG_API int rs_batch(void *handle, sy_img* img_data_array, int batch_size, rs_result* result); | |
95 | + | |
96 | + | |
97 | + /************************************************************************* | |
98 | + * FUNCTION: rs_release | |
99 | + * PURPOSE: 释放 | |
100 | + * PARAM: | |
101 | + [in] handle - handle | |
102 | + * RETURN: NULL | |
103 | + * NOTES: | |
104 | + *************************************************************************/ | |
105 | + ROADSEG_API void rs_release(void ** handle); | |
106 | + | |
107 | + | |
108 | + /************************************************************************* | |
109 | + * FUNCTION: rs_get_version | |
110 | + * PURPOSE: | |
111 | + * PARAM: NULL | |
112 | + * RETURN: 版本号 | |
113 | + * NOTES: | |
114 | + *************************************************************************/ | |
115 | + ROADSEG_API const char * rs_get_version(); | |
116 | + | |
117 | +#ifdef __cplusplus | |
118 | +}; | |
119 | +#endif | |
120 | + | |
121 | +#endif | ... | ... |
src/common/road_cnn/road_extractor.cpp
0 → 100755
1 | +#include "road_extractor.h" | |
2 | +#include <iostream> | |
3 | +#include "acl/acl.h" | |
4 | +#include "model_process.h" | |
5 | +#include "sy_errorinfo.h" | |
6 | +#include <time.h> | |
7 | +#include <sys/time.h> | |
8 | +#include <algorithm> | |
9 | + | |
10 | +using namespace std; | |
11 | + | |
12 | +namespace atlas_utils { | |
13 | + | |
14 | +int ROADExtract::Init(const char* modelPath) { | |
15 | + ACL_CALL(aclrtGetRunMode(&runMode_), SY_SUCCESS, SY_FAILED);//获取当前昇腾AI软件栈的运行模式,根据不同的运行模式,后续的接口调用方式不同 | |
16 | + ACL_CALL(model_.LoadModelFromFileWithMem(modelPath), SY_SUCCESS, SY_FAILED);//从文件加载离线模型数据,由用户自行管理模型运行的内存 | |
17 | + ACL_CALL(model_.CreateDesc(), SY_SUCCESS, SY_FAILED);//获取模型的描述信息 | |
18 | + ACL_CALL(model_.CreateOutput(outDims_), SY_SUCCESS, SY_FAILED); | |
19 | + ACL_CALL(model_.GetInputDims(inDims_), SY_SUCCESS, SY_FAILED); | |
20 | + modelHeight_ = inDims_[0][1]; | |
21 | + modelWidth_ = inDims_[0][2]; | |
22 | + | |
23 | + return SY_SUCCESS; | |
24 | +} | |
25 | + | |
26 | + | |
27 | +int ROADExtract::Inference(ImageData& input) { | |
28 | + model_.CreateInput(input.data.get(), input.size); | |
29 | + ACL_CALL(model_.Execute(), SY_SUCCESS, SY_FAILED); | |
30 | + model_.DestroyInput(); //需调用CreateInput的销毁类接口DestroyInput!!! | |
31 | + return SY_SUCCESS; | |
32 | +} | |
33 | + | |
34 | +int ROADExtract::GetInputWidth() { | |
35 | + return modelWidth_; | |
36 | +} | |
37 | + | |
38 | +int ROADExtract::GetInputHeight() { | |
39 | + return modelHeight_; | |
40 | +} | |
41 | + | |
42 | +int ROADExtract::PostProcess(vector<float>& results) { | |
43 | + aclmdlDataset* modelOutput = model_.GetModelOutputData(); | |
44 | + int outDatasetNum = aclmdlGetDatasetNumBuffers(modelOutput); | |
45 | + for (int i = 0; i < outDatasetNum; i++) { | |
46 | + aclDataBuffer* dataBuffer = aclmdlGetDatasetBuffer(modelOutput, i); | |
47 | + if (dataBuffer == nullptr) { | |
48 | + return SY_FAILED; | |
49 | + } | |
50 | + | |
51 | + uint32_t dataBufferSize = aclGetDataBufferSize(dataBuffer); | |
52 | + void* data = aclGetDataBufferAddr(dataBuffer); | |
53 | + if (data == nullptr) { | |
54 | + return SY_FAILED; | |
55 | + } | |
56 | + | |
57 | + int length = dataBufferSize/sizeof(float); | |
58 | + // float outInfo[length]; //栈上分配,受栈大小限制,数组过大可能导致栈溢出 | |
59 | + float* outInfo = new float[length]; //堆上分配 | |
60 | + if (runMode_ == ACL_HOST) { | |
61 | + ACL_CALL(aclrtMemcpy(outInfo, dataBufferSize, data, dataBufferSize, ACL_MEMCPY_DEVICE_TO_HOST),ACL_SUCCESS, SY_FAILED); | |
62 | + } | |
63 | + else { | |
64 | + ACL_CALL(aclrtMemcpy(outInfo, dataBufferSize, data, dataBufferSize, ACL_MEMCPY_DEVICE_TO_DEVICE),ACL_SUCCESS, SY_FAILED); | |
65 | + } | |
66 | + | |
67 | + for(uint32_t b = 0; b < length; b++) { | |
68 | + results.emplace_back(outInfo[b]); | |
69 | + } | |
70 | + | |
71 | + delete[] outInfo; outInfo = nullptr; | |
72 | + } | |
73 | + | |
74 | + return SY_SUCCESS; | |
75 | +} | |
76 | + | |
77 | +void ROADExtract::Release() { | |
78 | + model_.Unload(); | |
79 | + model_.DestroyDesc(); | |
80 | + model_.DestroyOutput(); | |
81 | +} | |
82 | + | |
83 | +} | ... | ... |
src/common/road_cnn/road_extractor.h
0 → 100755
1 | +#ifndef _ROAD_EXTRACT_H_ | |
2 | +#define _ROAD_EXTRACT_H_ | |
3 | + | |
4 | +#include <memory> | |
5 | +#include "utils.h" | |
6 | +#include "acl/acl.h" | |
7 | +#include "model_process.h" | |
8 | + | |
9 | +using namespace std; | |
10 | + | |
11 | +namespace atlas_utils { | |
12 | + | |
13 | + | |
14 | +#ifndef DATA_TYPE_SIZE | |
15 | +#define DATA_TYPE_SIZE 4 | |
16 | +#endif | |
17 | + | |
18 | +class ROADExtract { | |
19 | +public: | |
20 | + struct ConfigParams { | |
21 | + float confThr = 0.0; | |
22 | + }; | |
23 | + | |
24 | + ROADExtract() {} | |
25 | + ~ROADExtract() { | |
26 | + Release(); | |
27 | + } | |
28 | + | |
29 | + int Init(const char* modelPath); | |
30 | + int Inference(ImageData& input); | |
31 | + int PostProcess(vector<float>& result); | |
32 | + | |
33 | + int GetInputWidth(); | |
34 | + int GetInputHeight(); | |
35 | + | |
36 | + ConfigParams config; | |
37 | + | |
38 | +private: | |
39 | + void Release(); | |
40 | + | |
41 | + vector<vector<int>> outDims_; | |
42 | + vector<vector<int>> inDims_; | |
43 | + ModelProcess model_; | |
44 | + uint32_t modelWidth_; | |
45 | + uint32_t modelHeight_; | |
46 | + aclrtRunMode runMode_; | |
47 | + | |
48 | +}; | |
49 | + | |
50 | +} | |
51 | + | |
52 | +#endif | ... | ... |