forked from Smorodov/Multitarget-tracker
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathYoloDarknetDetector.cpp
More file actions
217 lines (189 loc) · 6.74 KB
/
YoloDarknetDetector.cpp
File metadata and controls
217 lines (189 loc) · 6.74 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
#include <fstream>
#include "YoloDarknetDetector.h"
#include "nms.h"
///
/// \brief YoloDarknetDetector::YoloDarknetDetector
/// \param gray
///
YoloDarknetDetector::YoloDarknetDetector(const cv::UMat& colorFrame)
: BaseDetector(colorFrame)
{
m_classNames = { "background",
"aeroplane", "bicycle", "bird", "boat",
"bottle", "bus", "car", "cat", "chair",
"cow", "diningtable", "dog", "horse",
"motorbike", "person", "pottedplant",
"sheep", "sofa", "train", "tvmonitor" };
}
///
/// \brief YoloDarknetDetector::~YoloDarknetDetector
///
YoloDarknetDetector::~YoloDarknetDetector(void)
{
}
///
/// \brief YoloDarknetDetector::Init
/// \return
///
bool YoloDarknetDetector::Init(const config_t& config)
{
m_detector.reset();
auto modelConfiguration = config.find("modelConfiguration");
auto modelBinary = config.find("modelBinary");
if (modelConfiguration == config.end() || modelBinary == config.end())
return false;
int currGPUID = 0;
auto gpuId = config.find("gpuId");
if (gpuId != config.end())
currGPUID = std::max(0, std::stoi(gpuId->second));
m_detector = std::make_unique<Detector>(modelConfiguration->second, modelBinary->second, currGPUID);
m_detector->nms = 0.2f;
auto classNames = config.find("classNames");
if (classNames != config.end())
{
std::ifstream classNamesFile(classNames->second);
if (classNamesFile.is_open())
{
m_classNames.clear();
std::string className;
for (; std::getline(classNamesFile, className); )
{
className.erase(className.find_last_not_of(" \t\n\r\f\v") + 1);
m_classNames.push_back(className);
}
}
}
auto confidenceThreshold = config.find("confidenceThreshold");
if (confidenceThreshold != config.end())
m_confidenceThreshold = std::stof(confidenceThreshold->second);
auto maxCropRatio = config.find("maxCropRatio");
if (maxCropRatio != config.end())
m_maxCropRatio = std::stof(maxCropRatio->second);
m_classesWhiteList.clear();
auto whiteRange = config.equal_range("white_list");
for (auto it = whiteRange.first; it != whiteRange.second; ++it)
{
m_classesWhiteList.insert(it->second);
}
bool correct = m_detector.get() != nullptr;
return correct;
}
///
/// \brief YoloDarknetDetector::Detect
/// \param gray
///
void YoloDarknetDetector::Detect(const cv::UMat& colorFrame)
{
m_regions.clear();
cv::Mat colorMat = colorFrame.getMat(cv::ACCESS_READ);
if (m_maxCropRatio <= 0)
{
Detect(colorMat, m_regions);
}
else
{
std::vector<cv::Rect> crops = GetCrops(m_maxCropRatio, cv::Size(m_detector->get_net_width(), m_detector->get_net_height()), colorMat.size());
regions_t tmpRegions;
for (size_t i = 0; i < crops.size(); ++i)
{
const auto& crop = crops[i];
//std::cout << "Crop " << i << ": " << crop << std::endl;
DetectInCrop(colorMat, crop, tmpRegions);
}
//det_num_pair* network_predict_batch(network *net, image im, int batch_size, int w, int h, float thresh, float hier, int *map, int relative, int letter);
//LIB_API void free_batch_detections(det_num_pair *det_num_pairs, int n);
if (crops.size() > 1)
{
nms3<CRegion>(tmpRegions, m_regions, 0.4f,
[](const CRegion& reg) { return reg.m_brect; },
[](const CRegion& reg) { return reg.m_confidence; },
[](const CRegion& reg) { return reg.m_type; },
0, 0.f);
//std::cout << "nms for " << tmpRegions.size() << " objects - result " << m_regions.size() << std::endl;
}
}
//std::cout << "Finally " << m_regions.size() << " objects, " << colorMat.u->refcount << ", " << colorMat.u->urefcount << std::endl;
}
///
/// \brief YoloDarknetDetector::DetectInCrop
/// \param colorFrame
/// \param crop
/// \param tmpRegions
///
void YoloDarknetDetector::DetectInCrop(const cv::Mat& colorFrame, const cv::Rect& crop, regions_t& tmpRegions)
{
cv::Size netSize(m_detector->get_net_width(), m_detector->get_net_height());
if (crop.width == netSize.width && crop.height == netSize.height)
m_tmpImg = colorFrame(crop);
else
cv::resize(colorFrame(crop), m_tmpImg, netSize, 0, 0, cv::INTER_LINEAR);
image_t detImage;
FillImg(detImage);
std::vector<bbox_t> detects = m_detector->detect(detImage, m_confidenceThreshold, false);
float wk = (float)crop.width / detImage.w;
float hk = (float)crop.height / detImage.h;
for (const bbox_t& bbox : detects)
{
if (m_classesWhiteList.empty() || m_classesWhiteList.find(m_classNames[bbox.obj_id]) != std::end(m_classesWhiteList))
tmpRegions.emplace_back(cv::Rect(cvRound(wk * bbox.x) + crop.x, cvRound(hk * bbox.y) + crop.y, cvRound(wk * bbox.w), cvRound(hk * bbox.h)), m_classNames[bbox.obj_id], bbox.prob);
}
if (crop.width == netSize.width && crop.height == netSize.height)
m_tmpImg.release();
//std::cout << "Detected " << detects.size() << " objects" << std::endl;
}
///
/// \brief YoloDarknetDetector::Detect
/// \param colorFrame
/// \param crop
/// \param tmpRegions
///
void YoloDarknetDetector::Detect(const cv::Mat& colorFrame, regions_t& tmpRegions)
{
cv::Size netSize(m_detector->get_net_width(), m_detector->get_net_height());
if (colorFrame.cols == netSize.width && colorFrame.rows == netSize.height)
m_tmpImg = colorFrame;
else
cv::resize(colorFrame, m_tmpImg, netSize, 0, 0, cv::INTER_LINEAR);
image_t detImage;
FillImg(detImage);
std::vector<bbox_t> detects = m_detector->detect(detImage, m_confidenceThreshold, false);
float wk = (float)colorFrame.cols / detImage.w;
float hk = (float)colorFrame.rows / detImage.h;
for (const bbox_t& bbox : detects)
{
if (m_classesWhiteList.empty() || m_classesWhiteList.find(m_classNames[bbox.obj_id]) != std::end(m_classesWhiteList))
tmpRegions.emplace_back(cv::Rect(cvRound(wk * bbox.x), cvRound(hk * bbox.y), cvRound(wk * bbox.w), cvRound(hk * bbox.h)), m_classNames[bbox.obj_id], bbox.prob);
}
//std::cout << "Detected " << detects.size() << " objects" << std::endl;
}
///
/// \brief YoloDarknetDetector::FillImg
/// \param detImage
///
void YoloDarknetDetector::FillImg(image_t& detImage)
{
detImage.w = m_tmpImg.cols;
detImage.h = m_tmpImg.rows;
detImage.c = m_tmpImg.channels();
assert(detImage.c == 3);
if (detImage.w * detImage.h * detImage.c != m_tmpBuf.size())
m_tmpBuf.resize(detImage.w * detImage.h * detImage.c);
detImage.data = &m_tmpBuf[0];
const int h = detImage.h;
const int w = detImage.w;
constexpr float knorm = 1.f / 255.f;
for (int y = 0; y < h; ++y)
{
for (int c = 0; c < 3; ++c)
{
const unsigned char *data = m_tmpImg.ptr(y) + 2 - c;
float* fdata = detImage.data + c * w * h + y * w;
for (int x = 0; x < w; ++x)
{
*fdata = knorm * data[0];
++fdata;
data += 3;
}
}
}
}