Commit 8b083a9d authored by xin.wang.waytous's avatar xin.wang.waytous

task(mots,fusion,bsw,dms)

parent 5d1de915
...@@ -61,6 +61,7 @@ ...@@ -61,6 +61,7 @@
"memory_resource": "cpp", "memory_resource": "cpp",
"random": "cpp", "random": "cpp",
"string": "cpp", "string": "cpp",
"unordered_set": "cpp" "unordered_set": "cpp",
"dense": "cpp"
} }
} }
\ No newline at end of file
...@@ -3,7 +3,7 @@ ...@@ -3,7 +3,7 @@
cmake_minimum_required(VERSION 3.5) cmake_minimum_required(VERSION 3.5)
project(DeepInfer) project(WaytousDeepInfer)
# cuda opencv # cuda opencv
find_package(CUDA REQUIRED) find_package(CUDA REQUIRED)
...@@ -60,12 +60,12 @@ set(CMAKE_CUDA_ARCHITECTURES 35 50 72) ...@@ -60,12 +60,12 @@ set(CMAKE_CUDA_ARCHITECTURES 35 50 72)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wfatal-errors -Ofast") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wfatal-errors -Ofast")
list(APPEND CUDA_NVCC_FLAGS "-D_FORCE_INLINES -Xcompiler -fPIC") list(APPEND CUDA_NVCC_FLAGS "-D_FORCE_INLINES -Xcompiler -fPIC")
set(PROJECT_CUDA_LIB deepinfer_cuda_cuda) set(PROJECT_CUDA_LIB waytous_deepinfer_cuda)
set(PROJECT_LIB deepinfer_cuda) set(PROJECT_LIB waytous_deepinfer)
message(WARNING ${PROJECT_LIB} ${DEP_LIBS}) message(WARNING ${PROJECT_LIB} ${DEP_LIBS})
add_subdirectory(src) add_subdirectory(src)
list(APPEND EXTRA_LIBS ${PROJECT_LIB}) list(APPEND EXTRA_LIBS ${PROJECT_LIB} ${PROJECT_CUDA_LIB})
list(APPEND EXTRA_INCLUDES "${PROJECT_SOURCE_DIR}/src") list(APPEND EXTRA_INCLUDES "${PROJECT_SOURCE_DIR}/src")
add_executable(main main.cpp) add_executable(main main.cpp)
......
configRootPath: /home/wangxin/projects/waytous/DeepInfer
device: 2
segmentorName: CameraModel
segmentorConfigPath: configs/tasks/mots/trades.yaml
name: TraDeS name: TraDeS
inputNames: [cvImage1] inputNames: [cvImage1]
outputNames: [segInstances1] outputNames: [trackedDetections1]
globalParams: globalParams:
inferBatchSize: 1 inferBatchSize: 1
inputWidth: 640 inputWidth: 640
...@@ -22,17 +22,17 @@ units: ...@@ -22,17 +22,17 @@ units:
- -
name: TRTInference name: TRTInference
inputNames: [resizeNormImages] inputNames: [resizeNormImages]
outputNames: [hm, reh, wh, conv_weight, seg_feat] outputNames: [hm, reg, wh, conv_weight, seg_feat]
runMode: 1 # 0-fp32 1-fp16 2-int8 (int8 not supported) runMode: 1 # 0-fp32 1-fp16 2-int8 (int8 not supported)
weightsPath: "configs/mots/trades_segv3.onnx" weightsPath: "configs/tasks/mots/trades_segv3.onnx"
engineFile: "configs/mots/trades_segv3_fp16.engine" engineFile: "configs/tasks/mots/trades_segv3_fp16.engine"
# calibImgPathFile: "configs/mots/trades_calib_imgs.txt" # calibImgPathFile: "configs/tasks/mots/trades_calib_imgs.txt"
# calibTableCache: "configs/mots/trades_calib_table.cache" # calibTableCache: "configs/tasks/mots/trades_calib_table.cache"
inferDynamic: false inferDynamic: false
maxBatchSize: 1 maxBatchSize: 1
- -
name: TraDesPostProcess name: TraDesPostProcess
inputNames: [hm, reh, wh, conv_weight, seg_feat, uint8Image1] inputNames: [hm, reg, wh, conv_weight, seg_feat, uint8Image1]
outputNames: [segInstances1] outputNames: [segInstances1]
scoreThreshold: 0.2 scoreThreshold: 0.2
truncatedThreshold: 0.05 truncatedThreshold: 0.05
...@@ -42,6 +42,16 @@ units: ...@@ -42,6 +42,16 @@ units:
downScale: 4 downScale: 4
segDims: 64 segDims: 64
maxCntsLength: 500 maxCntsLength: 500
-
name: ByteTracker
inputNames: [segInstances1]
outputNames: [trackedDetections1]
frame_rate: 20
track_buffer: 30
track_thresh: 0.2
high_thresh: 0.2
match_thresh: 0.8
init_frames: 0
......
configRootPath: /home/wangxin/projects/waytous/DeepInfer
device: 3
detectorName: CameraModel
detectorConfigPath: configs/tasks/thermal/yolov5.yaml
...@@ -28,10 +28,10 @@ units: ...@@ -28,10 +28,10 @@ units:
inputNames: [resizeNormImages] inputNames: [resizeNormImages]
outputNames: [num_detections, nmsed_boxes, nmsed_scores, nmsed_classes] outputNames: [num_detections, nmsed_boxes, nmsed_scores, nmsed_classes]
runMode: 1 # 0-fp32 1-fp16 2-int8 (int8 not supported) runMode: 1 # 0-fp32 1-fp16 2-int8 (int8 not supported)
weightsPath: "configs/thermal/yolov5s_640x640_thermal.wts" weightsPath: "configs/tasks/thermal/yolov5s_640x640_thermal.wts"
engineFile: "configs/thermal/yolov5s_640x640_thermal_fp16.engine" engineFile: "configs/tasks/thermal/yolov5s_640x640_thermal_fp16.engine"
calibImgPathFile: "configs/thermal/yolov5s_calib_imgs.txt" # calibImgPathFile: "configs/tasks/thermal/yolov5s_calib_imgs.txt"
calibTableCache: "configs/thermal/yolov5s_calib_table.cache" # calibTableCache: "configs/tasks/thermal/yolov5s_calib_table.cache"
inferDynamic: true inferDynamic: true
maxBatchSize: 4 maxBatchSize: 4
classNumber: 2 classNumber: 2
...@@ -71,6 +71,16 @@ units: ...@@ -71,6 +71,16 @@ units:
match_thresh: 0.8 match_thresh: 0.8
# output detection after it was tracked in x frames # output detection after it was tracked in x frames
init_frames: 0 init_frames: 0
-
name: ByteTracker
inputNames: [detections2]
outputNames: [trackedDetections2]
frame_rate: 20
track_buffer: 30
track_thresh: 0.2
high_thresh: 0.2
match_thresh: 0.8
init_frames: 0
......
...@@ -25,7 +25,7 @@ std::vector<std::string> stringSplit(const std::string& str, char delim) { ...@@ -25,7 +25,7 @@ std::vector<std::string> stringSplit(const std::string& str, char delim) {
} }
int main(int argc, char** argv){ int main(int argc, char** argv){
google::InitGoogleLogging("WARNING"); // google::InitGoogleLogging("INFO");
if(argc < 6){ if(argc < 6){
printf("wrong args."); printf("wrong args.");
printf("use like ./main task video/image configpath src dst."); printf("use like ./main task video/image configpath src dst.");
...@@ -58,6 +58,7 @@ int main(int argc, char** argv){ ...@@ -58,6 +58,7 @@ int main(int argc, char** argv){
std::cout << "before infer." << std::endl; std::cout << "before infer." << std::endl;
auto e1 = std::chrono::system_clock::now(); auto e1 = std::chrono::system_clock::now();
for(int i=0; i<100; i++){ for(int i=0; i<100; i++){
outputs.clear();
t->Exec(inputs, outputs); t->Exec(inputs, outputs);
} }
auto e2 = std::chrono::system_clock::now(); auto e2 = std::chrono::system_clock::now();
......
project(DeepInferModel) project(DeepInfer)
......
...@@ -60,6 +60,25 @@ inline float euclidean(float x1, float y1, float x2, float y2){ ...@@ -60,6 +60,25 @@ inline float euclidean(float x1, float y1, float x2, float y2){
} }
void softmax(float *x, int length){
float max = x[0];
float sum = 0.0;
for(int i=0; i<length; i++){
if(max < x[i]){
max = x[i];
}
}
for(int i=0; i<length; i++){
x[i] = std::exp(x[i] - max);
sum += x[i];
}
for(int i=0; i<length; i++){
x[i] /= sum;
}
}
} //namespace common } //namespace common
} //namspace deepinfer } //namspace deepinfer
} //namespace waytous } //namespace waytous
......
...@@ -5,11 +5,17 @@ namespace waytous { ...@@ -5,11 +5,17 @@ namespace waytous {
namespace deepinfer { namespace deepinfer {
namespace interfaces { namespace interfaces {
// cudafree global variable -> cuda_error 29
BaseIOMap &GlobalBaseIOMap(){
static BaseIOMap GlobalIOMap;
return GlobalIOMap;
}
BaseIOPtr GetIOPtr(std::string& ioName){ BaseIOPtr GetIOPtr(std::string& ioName){
auto iter = GlobalIOMap.find(ioName); auto& gmap = GlobalBaseIOMap();
if (iter == GlobalIOMap.end()) { auto iter = gmap.find(ioName);
if (iter == gmap.end()) {
return nullptr; return nullptr;
} }
return iter->second; return iter->second;
...@@ -17,7 +23,8 @@ BaseIOPtr GetIOPtr(std::string& ioName){ ...@@ -17,7 +23,8 @@ BaseIOPtr GetIOPtr(std::string& ioName){
void SetIOPtr(std::string& ioName, BaseIOPtr src){ void SetIOPtr(std::string& ioName, BaseIOPtr src){
GlobalIOMap[ioName] = src; auto& gmap = GlobalBaseIOMap();
gmap[ioName] = src;
} }
......
...@@ -23,7 +23,7 @@ using BaseIOPtr = std::shared_ptr<BaseIO>; ...@@ -23,7 +23,7 @@ using BaseIOPtr = std::shared_ptr<BaseIO>;
typedef std::map<std::string, BaseIOPtr> BaseIOMap; typedef std::map<std::string, BaseIOPtr> BaseIOMap;
static BaseIOMap GlobalIOMap; BaseIOMap &GlobalBaseIOMap();
BaseIOPtr GetIOPtr(std::string& ioName); BaseIOPtr GetIOPtr(std::string& ioName);
......
...@@ -24,11 +24,11 @@ class BaseModel{ ...@@ -24,11 +24,11 @@ class BaseModel{
public: public:
BaseModel() = default; BaseModel() = default;
virtual ~BaseModel() = default; virtual ~BaseModel() = default;
virtual bool Init(std::string& configPath); virtual bool Init(std::string& configPath) = 0;
// for camera image infer // for camera image infer, dynamic_cast need base-class-func to implemented or pure-virtual
virtual bool Exec(std::vector<cv::Mat*> inputs, std::vector<BaseIOPtr>& outputs); virtual bool Exec(std::vector<cv::Mat*> inputs, std::vector<BaseIOPtr>& outputs){};
virtual bool Exec(std::vector<base::Image8UPtr> inputs, std::vector<BaseIOPtr>& outputs); virtual bool Exec(std::vector<base::Image8UPtr> inputs, std::vector<BaseIOPtr>& outputs){};
virtual std::string Name(){ virtual std::string Name(){
return "BaseModel"; return "BaseModel";
......
...@@ -6,6 +6,7 @@ ...@@ -6,6 +6,7 @@
#include <yaml-cpp/yaml.h> #include <yaml-cpp/yaml.h>
#include "common/register.h" #include "common/register.h"
#include "interfaces/base_model.h"
#include "interfaces/base_io.h" #include "interfaces/base_io.h"
...@@ -19,10 +20,10 @@ public: ...@@ -19,10 +20,10 @@ public:
BaseTask() = default; BaseTask() = default;
virtual ~BaseTask() = default; virtual ~BaseTask() = default;
virtual bool Init(std::string& taskConfigPath); virtual bool Init(std::string& taskConfigPath) = 0;
// camera image // camera image
virtual bool Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs); virtual bool Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs) = 0;
virtual void Visualize(cv::Mat* image, interfaces::BaseIOPtr outs) = 0; virtual void Visualize(cv::Mat* image, interfaces::BaseIOPtr outs) = 0;
virtual cv::Scalar get_color(int idx); virtual cv::Scalar get_color(int idx);
......
...@@ -5,8 +5,8 @@ namespace deepinfer { ...@@ -5,8 +5,8 @@ namespace deepinfer {
namespace interfaces { namespace interfaces {
bool BaseUnit::Init(YAML::Node& node, YAML::Node& globalParamNode){ bool BaseUnit::Init(YAML::Node& node, YAML::Node& globalParamNode){
inputNames = node.as<std::vector<std::string>>("inputNames"); inputNames = node["inputNames"].as<std::vector<std::string>>();
outputNames = node.as<std::vector<std::string>>("outputNames"); outputNames = node["outputNames"].as<std::vector<std::string>>();
inferBatchSize = globalParamNode["inferBatchSize"].as<int>(); // default=1 inferBatchSize = globalParamNode["inferBatchSize"].as<int>(); // default=1
inputHeight = globalParamNode["inputHeight"].as<int>(); inputHeight = globalParamNode["inputHeight"].as<int>();
inputWidth = globalParamNode["inputWidth"].as<int>(); inputWidth = globalParamNode["inputWidth"].as<int>();
......
#include "libs/fusioner/bayesian_fusioner.h"
namespace waytous {
namespace deepinfer {
namespace fusioner {
bool BayesianFusioner::Init(YAML::Node& node, YAML::Node& globalParamNode) {
if(!BaseUnit::Init(node, globalParamNode)){
LOG_WARN << "Init trades postprocess error";
return false;
};
NMSThreshold = node["NMSThreshold"].as<float>();
std::string methodStr = node["matchMethod"].as<std::string>();
auto method = MethodName2Type.find(methodStr);
if(method == MethodName2Type.end()){
LOG_WARN << "Not supported match method " << methodStr;
return false;
}
matchMethod = method->second;
return true;
}
bool BayesianFusioner::Exec(){
std::vector<ios::Det2DPtr> all_objects;
for(int i=0; i<inputNames.size(); i++){
auto inputName = inputNames[i];
auto ptr = std::dynamic_pointer_cast<ios::Detection2Ds>(interfaces::GetIOPtr(inputName));
if (ptr == nullptr){
LOG_ERROR << "BayesianFusioner input " << inputName << " haven't been init or doesn't exist.";
return false;
}
for(auto d: ptr->detections){
d->camera_id = i;
all_objects.push_back(d);
}
}
// nms
std::vector<int> indices;
std::vector<bool> deleted(all_objects.size(), false);
for(int i=0; i<all_objects.size(); i++){
indices.push_back(i);
}
std::sort(indices.begin(), indices.end(),
[&](int a, int b){ return (all_objects[a]->confidence - float(all_objects[a]->truncated)) > (all_objects[b]->confidence - float(all_objects[b]->truncated));}
);
auto fusioned_objects = std::make_shared<ios::Detection2Ds>(ios::Detection2Ds());
for(size_t i=0; i < indices.size(); i++){
if(!deleted[indices[i]]){
std::vector<ios::Det2DPtr> matched_objs;
auto main_obj = all_objects[indices[i]];
matched_objs.push_back(main_obj);
for(size_t j=i+1; j < indices.size(); j++){
// only merge obj from different sensor
if(!deleted[indices[j]] && (main_obj->camera_id != all_objects[indices[j]]->camera_id)
&& Measure(main_obj, all_objects[indices[j]]) > NMSThreshold){
deleted[indices[j]] = true;
matched_objs.push_back(all_objects[indices[j]]);
}
}
float pos_sum = 0;
float neg_sum = 0;
for(auto& obj : matched_objs){
pos_sum += std::log(obj->confidence);
neg_sum += std::log(1 - obj->confidence);
}
pos_sum = std::exp(pos_sum);
neg_sum = std::exp(neg_sum);
main_obj->confidence = pos_sum / (pos_sum + neg_sum);
// if()
fusioned_objects->detections.push_back(main_obj);
}
}
return true;
}
float BayesianFusioner::Measure(ios::Det2DPtr obja, ios::Det2DPtr objb){
if(obja->class_name != objb->class_name){
return 0;
}
float insection_area = obja->insectionArea(objb);
float measurement = 0;
switch (matchMethod)
{
case BayesianFusionMatchMethod::IOU:{
measurement = insection_area / (obja->area() + objb->area() - insection_area);
break;
}
case BayesianFusionMatchMethod::IOA:{
measurement = insection_area / (objb->truncated ? objb->area() : obja->area());
break;
}
case BayesianFusionMatchMethod::GIOU:{
float rect_area_sum = (obja->area() + objb->area() - insection_area);
float out_area = obja->uniArea(objb);
measurement = insection_area / rect_area_sum - (out_area - rect_area_sum) / out_area;
break;
}
case BayesianFusionMatchMethod::CIOU:{
float iou = insection_area / (obja->area() + objb->area() - insection_area);
float a = std::atan((obja->x2 - obja->x1) / (obja->y2 - obja->y1)) -
std::atan((objb->x2 - objb->x1) / (objb->y2 - objb->y1));
float pi = 3.1415926;
float v = (4.0 / (pi * pi)) * (a * a);
float alpha = v / (1 - iou + v);
float xc_a = obja->x1 + (obja->x2 - obja->x1) / 2;
float yc_a = obja->y1 + (obja->y2 - obja->y1) / 2;
float xc_b = objb->x1 + (objb->x2 - objb->x1) / 2;
float yc_b = objb->y1 + (objb->y2 - objb->y1) / 2;
float p2 = std::pow(xc_a - xc_b, 2) + std::pow(yc_a - yc_b, 2);
float out_width = std::max(obja->x2, objb->x2) - std::min(obja->x1, objb->x1);
float out_height = std::max(obja->y2, objb->y2) - std::min(obja->y1, objb->y1);
float c2 = std::pow(out_width, 2) + std::pow(out_height, 2);
measurement = iou - p2 / c2 - alpha * v;
break;
}
default:
break;
}
return measurement;
};
std::string BayesianFusioner::Name() {
return "BayesianFusioner";
};
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#ifndef WAYTOUS_DEEPINFER_BAYESIAN_FUSIONER_H_
#define WAYTOUS_DEEPINFER_BAYESIAN_FUSIONER_H_
#include <algorithm>
#include <map>
#include <string>
#include "interfaces/base_unit.h"
#include "libs/ios/normal_ios.h"
#include "libs/ios/detection.h"
namespace waytous{
namespace deepinfer{
namespace fusioner{
enum class BayesianFusionMatchMethod{
IOU = 0,
GIOU = 1,
CIOU = 2,
IOA = 3
};
class BayesianFusioner: public interfaces::BaseUnit{
public:
std::map<std::string, BayesianFusionMatchMethod> MethodName2Type = {
{"IOU", BayesianFusionMatchMethod::IOU},
{"GIOU", BayesianFusionMatchMethod::GIOU},
{"CIOU", BayesianFusionMatchMethod::CIOU},
{"IOA", BayesianFusionMatchMethod::IOA}
};
bool Init(YAML::Node& node, YAML::Node& globalParamNode) override;
bool Exec() override;
std::string Name() override;
float Measure(ios::Det2DPtr obja, ios::Det2DPtr objb);
public:
BayesianFusionMatchMethod matchMethod = BayesianFusionMatchMethod::IOU;
float NMSThreshold = 0.5;
};
DEEPINFER_REGISTER_UNIT(BayesianFusioner);
} //namespace fusioner
} //namspace deepinfer
} //namespace waytous
#endif
...@@ -71,6 +71,10 @@ bool TRTInference::Init(YAML::Node& configNode, YAML::Node& globalParamNode){ ...@@ -71,6 +71,10 @@ bool TRTInference::Init(YAML::Node& configNode, YAML::Node& globalParamNode){
for (auto inputName: inputNames){ for (auto inputName: inputNames){
auto input = std::dynamic_pointer_cast<ios::NormalIO>(interfaces::GetIOPtr(inputName)); auto input = std::dynamic_pointer_cast<ios::NormalIO>(interfaces::GetIOPtr(inputName));
if (input == nullptr){
LOG_ERROR << "inference engine input " << inputName << " haven't been init or doesn't exist.";
return false;
}
blobs_.insert(std::make_pair(inputName, input->data_)); blobs_.insert(std::make_pair(inputName, input->data_));
auto binding = input->data_->mutable_gpu_data(); auto binding = input->data_->mutable_gpu_data();
mBindings.emplace_back(static_cast<void*>(binding)); mBindings.emplace_back(static_cast<void*>(binding));
...@@ -85,13 +89,16 @@ bool TRTInference::Init(YAML::Node& configNode, YAML::Node& globalParamNode){ ...@@ -85,13 +89,16 @@ bool TRTInference::Init(YAML::Node& configNode, YAML::Node& globalParamNode){
nvinfer1::Dims dims = mEngine->getBindingDimensions(i); nvinfer1::Dims dims = mEngine->getBindingDimensions(i);
nvinfer1::DataType dtype = mEngine->getBindingDataType(i); nvinfer1::DataType dtype = mEngine->getBindingDataType(i);
std::string name = mEngine->getBindingName(i); std::string name = mEngine->getBindingName(i);
LOG_INFO << "engine output name: " << name;
std::vector<int> shape; std::vector<int> shape;
shape.push_back(inferBatchSize); shape.push_back(inferBatchSize);
for(int dindex = 0; dindex < dims.nbDims; dindex++){ for(int dindex = 0; dindex < dims.nbDims; dindex++){
shape.push_back(dims.d[dindex]); shape.push_back(dims.d[dindex]);
}; };
auto blob = std::make_shared<base::Blob<float>>(base::Blob<float>(shape)); //auto blob = std::make_shared<base::Blob<float>>(base::Blob<float>(shape)); // Blob(Blob)=delete
base::BlobPtr<float> blob;
blob.reset(new base::Blob<float>(shape));
blobs_.insert(std::make_pair(name, blob)); blobs_.insert(std::make_pair(name, blob));
auto output = std::make_shared<ios::NormalIO>(ios::NormalIO(blob)); auto output = std::make_shared<ios::NormalIO>(ios::NormalIO(blob));
interfaces::SetIOPtr(name, output); interfaces::SetIOPtr(name, output);
...@@ -131,7 +138,7 @@ bool TRTInference::BuildEngine(YAML::Node& configNode){ ...@@ -131,7 +138,7 @@ bool TRTInference::BuildEngine(YAML::Node& configNode){
} }
builder->setMaxBatchSize(maxBatchSize); builder->setMaxBatchSize(maxBatchSize);
builder->setMaxWorkspaceSize(1 << 30);// 1G builder->setMaxWorkspaceSize(2UL << 30);// 2G
int8EntroyCalibrator *calibrator = nullptr; int8EntroyCalibrator *calibrator = nullptr;
int runMode = configNode["runMode"].as<int>(); int runMode = configNode["runMode"].as<int>();
...@@ -240,6 +247,7 @@ bool TRTInference::Exec(){ ...@@ -240,6 +247,7 @@ bool TRTInference::Exec(){
blob->mutable_gpu_data(); blob->mutable_gpu_data();
} }
} }
return true;
} }
...@@ -248,9 +256,6 @@ std::string TRTInference::Name(){ ...@@ -248,9 +256,6 @@ std::string TRTInference::Name(){
} }
DEEPINFER_REGISTER_UNIT(TRTInference);
} // namespace inference } // namespace inference
} // namespace deepinfer } // namespace deepinfer
} // namespace waytous } // namespace waytous
......
...@@ -53,6 +53,7 @@ public: ...@@ -53,6 +53,7 @@ public:
bool inferDynamic = false; bool inferDynamic = false;
}; // class TRTInferenceEngine }; // class TRTInferenceEngine
DEEPINFER_REGISTER_UNIT(TRTInference);
} // namespace inference } // namespace inference
} // namespace deepinfer } // namespace deepinfer
......
...@@ -347,7 +347,7 @@ bool YoloV5TRTInference::BuildEngine(YAML::Node& configNode){ ...@@ -347,7 +347,7 @@ bool YoloV5TRTInference::BuildEngine(YAML::Node& configNode){
// Build engine // Build engine
builder->setMaxBatchSize(maxBatchSize); builder->setMaxBatchSize(maxBatchSize);
config->setMaxWorkspaceSize(maxBatchSize * (1 << 30)); // 1GB config->setMaxWorkspaceSize((maxBatchSize * (1UL << 30))); // 2GB
int8EntroyCalibrator *calibrator = nullptr; int8EntroyCalibrator *calibrator = nullptr;
if (runMode == 1){ if (runMode == 1){
config->setFlag(BuilderFlag::kFP16); config->setFlag(BuilderFlag::kFP16);
...@@ -405,7 +405,6 @@ std::string YoloV5TRTInference::Name(){ ...@@ -405,7 +405,6 @@ std::string YoloV5TRTInference::Name(){
} }
DEEPINFER_REGISTER_UNIT(YoloV5TRTInference);
} // namespace inference } // namespace inference
} // namespace deepinfer } // namespace deepinfer
......
...@@ -102,6 +102,7 @@ private: ...@@ -102,6 +102,7 @@ private:
}; };
DEEPINFER_REGISTER_UNIT(YoloV5TRTInference);
} // namespace inference } // namespace inference
......
...@@ -6,6 +6,10 @@ namespace deepinfer { ...@@ -6,6 +6,10 @@ namespace deepinfer {
namespace ios { namespace ios {
void Det2D::validCoordinate(){ void Det2D::validCoordinate(){
if(image_width <= 0 || image_height <= 0){
LOG_WARN << "Detection should set image_width > 0 and image_height > 0";
return;
}
x1 = iMIN(image_width - 1, iMAX(0, x1)); x1 = iMIN(image_width - 1, iMAX(0, x1));
x2 = iMIN(image_width - 1, iMAX(0, x2)); x2 = iMIN(image_width - 1, iMAX(0, x2));
y1 = iMIN(image_height - 1, iMAX(0, y1)); y1 = iMIN(image_height - 1, iMAX(0, y1));
...@@ -15,6 +19,8 @@ void Det2D::validCoordinate(){ ...@@ -15,6 +19,8 @@ void Det2D::validCoordinate(){
Det2DPtr Det2D::copy(){ Det2DPtr Det2D::copy(){
Det2DPtr obj = std::make_shared<Det2D>(Det2D()); Det2DPtr obj = std::make_shared<Det2D>(Det2D());
obj->image_height = this->image_height;
obj->image_width = this->image_width;
obj->x1 = this->x1; obj->x1 = this->x1;
obj->x2 = this->x2; obj->x2 = this->x2;
obj->y1 = this->y1; obj->y1 = this->y1;
...@@ -24,12 +30,16 @@ Det2DPtr Det2D::copy(){ ...@@ -24,12 +30,16 @@ Det2DPtr Det2D::copy(){
obj->class_name = this->class_name; obj->class_name = this->class_name;
obj->truncated = this->truncated; obj->truncated = this->truncated;
obj->track_id = this->track_id; obj->track_id = this->track_id;
if (obj->mask_ptr != nullptr){ obj->camera_id = this->camera_id;
if (this->mask_ptr != nullptr){
obj->mask_ptr.reset(new InstanceMask(this->mask_ptr.get())); obj->mask_ptr.reset(new InstanceMask(this->mask_ptr.get()));
} }
return obj;
} }
void Det2D::update(Det2DPtr obj_){ void Det2D::update(Det2DPtr obj_){
this->image_height = obj_->image_height;
this->image_width = obj_->image_width;
this->x1 = obj_->x1; this->x1 = obj_->x1;
this->x2 = obj_->x2; this->x2 = obj_->x2;
this->y1 = obj_->y1; this->y1 = obj_->y1;
...@@ -38,8 +48,9 @@ void Det2D::update(Det2DPtr obj_){ ...@@ -38,8 +48,9 @@ void Det2D::update(Det2DPtr obj_){
this->class_label = obj_->class_label; this->class_label = obj_->class_label;
this->class_name = obj_->class_name; this->class_name = obj_->class_name;
this->truncated = obj_->truncated; this->truncated = obj_->truncated;
this->track_id = obj_->track_id; // this->track_id = obj_->track_id;// don't update track_id, because they matched and get same track_id.
if (this->mask_ptr != nullptr){ this->camera_id = obj_->camera_id;
if (obj_->mask_ptr != nullptr){
this->mask_ptr->update(obj_->mask_ptr.get()); this->mask_ptr->update(obj_->mask_ptr.get());
} }
}; };
...@@ -52,6 +63,30 @@ void Det2D::update(std::vector<float>& tlbr){ ...@@ -52,6 +63,30 @@ void Det2D::update(std::vector<float>& tlbr){
this->y2 = tlbr[3]; this->y2 = tlbr[3];
}; };
float Det2D::area(){
return (x2 - x1) * (y2 - y1);
};
float Det2D::uniArea(Det2DPtr other){
float out_width = std::max(x2, other->x2) - std::min(x1, other->x1);
float out_height = std::max(y2, other->y2) - std::min(y1, other->y1);
return out_width * out_height;
};
float Det2D::insectionArea(Det2DPtr other){
float in_width = std::min(x2, other->x2) - std::max(x1, other->x1);
float in_height = std::min(y2, other->y2) - std::max(y1, other->y1);
if(in_width <= 0 || in_height <= 0){
return 0;
}
return in_width * in_height;
};
} // namespace ios } // namespace ios
} // namespace deepinfer } // namespace deepinfer
} // namespace waytous } // namespace waytous
......
...@@ -22,6 +22,8 @@ public: ...@@ -22,6 +22,8 @@ public:
}; };
using DetPtr = std::shared_ptr<Det>; using DetPtr = std::shared_ptr<Det>;
class Det2D;
using Det2DPtr = std::shared_ptr<Det2D>;
class Det2D : public Det{ class Det2D : public Det{
...@@ -30,6 +32,9 @@ public: ...@@ -30,6 +32,9 @@ public:
Det2DPtr copy(); Det2DPtr copy();
void update(Det2DPtr obj_); void update(Det2DPtr obj_);
void update(std::vector<float>& tlbr); void update(std::vector<float>& tlbr);
float area();
float uniArea(Det2DPtr other);
float insectionArea(Det2DPtr other);
public: public:
float image_width = 0, image_height = 0; float image_width = 0, image_height = 0;
...@@ -40,8 +45,8 @@ public: ...@@ -40,8 +45,8 @@ public:
bool truncated = false; bool truncated = false;
InstanceMaskPtr mask_ptr = nullptr; InstanceMaskPtr mask_ptr = nullptr;
int track_id = -1; int track_id = -1;
int camera_id = -1;
}; };
using Det2DPtr = std::shared_ptr<Det2D>;
......
#ifndef DEEPINFER_FACE_POSE_H_
#define DEEPINFER_FACE_POSE_H_
#include <vector>
#include <string>
#include "common/common.h"
#include "interfaces/base_io.h"
namespace waytous {
namespace deepinfer {
namespace ios {
class HeadPose: public interfaces::BaseIO{
public:
float yaw;
float pitch;
float roll;
};
using HeadPosePtr = std::shared_ptr<HeadPose>;
} // namespace ios
} // namespace deepinfer
} // namespace waytous
#endif
#ifndef DEEPINFER_LANDMARK_H_
#define DEEPINFER_LANDMARK_H_
#include <vector>
#include <string>
#include "common/common.h"
#include "interfaces/base_io.h"
namespace waytous {
namespace deepinfer {
namespace ios {
struct Point2D{
float x;
float y;
};
using Point2DPtr = std::shared_ptr<Point2D>;
class Landmarks: public interfaces::BaseIO{
public:
std::vector<Point2DPtr> landmarks;
};
using LandmarksPtr = std::shared_ptr<Landmarks>;
} // namespace ios
} // namespace deepinfer
} // namespace waytous
#endif
#include "libs/postprocessors/homo_project.h"
namespace waytous {
namespace deepinfer {
namespace postprocess {
bool HomoProject::Init(YAML::Node& node, YAML::Node& globalParamNode) {
if(!BaseUnit::Init(node, globalParamNode)){
LOG_WARN << "Init homo project error";
return false;
};
auto homoMatrixPath = node["homoMatrixPath"].as<std::string>();
std::string yaml_path = common::GetAbsolutePath(common::ConfigRoot::GetRootPath(), homoMatrixPath);
if (!common::PathExists(yaml_path)) {
LOG_INFO << yaml_path << " does not exist!";
return false;
}
YAML::Node node = YAML::LoadFile(yaml_path);
if (node.IsNull()) {
LOG_INFO << "Load " << yaml_path << " failed! please check!";
return false;
}
for(int i=0; i<9; i++){
camera_homo_to_main(i) = node["homography_matrix"]["data"][i].as<float>();
}
return true;
}
bool HomoProject::Exec(){
auto ptr = std::dynamic_pointer_cast<ios::Detection2Ds>(interfaces::GetIOPtr(inputNames[0]));
if (ptr == nullptr){
LOG_ERROR << "HomoProject input " << inputNames[0] << " haven't been init or doesn't exist.";
return false;
}
auto projected_dets = std::make_shared<ios::Detection2Ds>(ios::Detection2Ds());
Eigen::Matrix<float, 3, 2, Eigen::RowMajor> default_box, pbox;
default_box(4) = 1;
default_box(5) = 1;
for(auto& obj: ptr->detections){
ios::Det2DPtr projected_obj = obj->copy();
default_box(0) = obj->x1;
default_box(1) = obj->x2;
default_box(2) = obj->y1;
default_box(3) = obj->y2;
pbox = camera_homo_to_main * default_box;// projected to main space
projected_obj->x1 = pbox(0);
projected_obj->x2 = pbox(1);
projected_obj->y1 = pbox(2);
projected_obj->y2 = pbox(3);
projected_dets->detections.push_back(projected_obj);
}
interfaces::SetIOPtr(outputNames[0], projected_dets);
return true;
}
std::string HomoProject::Name() {
return "HomoProject";
};
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#ifndef DEEPINFER_POSTPROCESS_HOMO_PROJECT_H_
#define DEEPINFER_POSTPROCESS_HOMO_PROJECT_H_
#include <memory>
#include <string>
#include <Eigen/Dense>
#include "common/file.h"
#include "interfaces/base_unit.h"
#include "libs/ios/detection.h"
namespace waytous {
namespace deepinfer {
namespace postprocess {
class HomoProject: public interfaces::BaseUnit{
public:
bool Init(YAML::Node& node, YAML::Node& globalParamNode) override;
bool Exec() override;
std::string Name() override;
public:
Eigen::Matrix<float, 3, 3, Eigen::RowMajor> camera_homo_to_main;
};
DEEPINFER_REGISTER_UNIT(HomoProject);
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#endif
#include "libs/postprocessors/mobilefacenet_post.h"
namespace waytous {
namespace deepinfer {
namespace postprocess {
bool MobileFaceNetPostProcess::Init(YAML::Node& node, YAML::Node& globalParamNode) {
if(!BaseUnit::Init(node, globalParamNode)){
LOG_WARN << "Init trades postprocess error";
return false;
};
landmarkNumber = node["landmarkNumber"].as<int>();
return true;
}
bool MobileFaceNetPostProcess::Exec(){
if (inputNames.size() != 1 + outputNames.size()){
LOG_ERROR << "yolov5 postprocess, inputsize != 4 + ouputsize.";
return false;
}
auto input = std::dynamic_pointer_cast<ios::NormalIO>(interfaces::GetIOPtr(inputNames[0]));
if (input == nullptr){
LOG_ERROR << "WHENet postprocess input " << inputNames[0] << " haven't been init or doesn't exist.";
return false;
}
std::vector<base::Image8UPtr> inputImages;
for(int j=1; j<inputNames.size(); j++){
auto iName = inputNames[j];
auto iptr = std::dynamic_pointer_cast<ios::CameraSrcOut>(interfaces::GetIOPtr(iName));
if (iptr == nullptr){
LOG_ERROR << "YoloV5 postprocess input " << iName << " haven't been init or doesn't exist.";
return false;
}
inputImages.push_back(iptr->img_ptr_);
}
const float* points = input->data_->cpu_data();
for(int b=0; b<inputImages.size(); b++){
auto outName = outputNames[b];
float img_width = float(inputImages[b]->cols());
float img_height = float(inputImages[b]->rows());
float scalex = inputWidth / img_width;
float scaley = inputHeight / img_height;
if(fixAspectRatio){
scalex = scaley = std::min(scalex, scaley);
}
auto face_landmarks = std::make_shared<ios::Landmarks>(ios::Landmarks());
for(int l=0; l < landmarkNumber; l++){
ios::Point2DPtr lptr = std::make_shared<ios::Point2D>(ios::Point2D());
lptr->x = points[l * 2] * inputWidth / scalex;
lptr->y = points[l * 2 + 1] * inputHeight / scaley;
face_landmarks->landmarks.push_back(lptr);
}
interfaces::SetIOPtr(outputNames[b], face_landmarks);
}
return true;
}
std::string MobileFaceNetPostProcess::Name() {
return "MobileFaceNetPostProcess";
};
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#ifndef DEEPINFER_POSTPROCESS_MOBILEFACENET_H_
#define DEEPINFER_POSTPROCESS_MOBILEFACENET_H_
#include <cuda_runtime.h>
#include <cstdint>
#include "interfaces/base_unit.h"
#include "base/image.h"
#include "libs/ios/normal_ios.h"
#include "libs/ios/camera_ios.h"
#include "libs/ios/landmark.h"
namespace waytous {
namespace deepinfer {
namespace postprocess {
class MobileFaceNetPostProcess: public interfaces::BaseUnit{
public:
bool Init(YAML::Node& node, YAML::Node& globalParamNode) override;
bool Exec() override;
std::string Name() override;
public:
int landmarkNumber;
};
DEEPINFER_REGISTER_UNIT(MobileFaceNetPostProcess);
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#endif
...@@ -42,13 +42,21 @@ bool TraDesPostProcess::Exec() { ...@@ -42,13 +42,21 @@ bool TraDesPostProcess::Exec() {
for(int i=0; i<5; i++){ for(int i=0; i<5; i++){
auto iName = inputNames[i]; auto iName = inputNames[i];
auto p = std::dynamic_pointer_cast<ios::NormalIO>(interfaces::GetIOPtr(iName)); auto p = std::dynamic_pointer_cast<ios::NormalIO>(interfaces::GetIOPtr(iName));
if (p == nullptr){
LOG_ERROR << "TraDeS postprocess input " << iName << " haven't been init or doesn't exist.";
return false;
}
inputs.push_back(p->data_); inputs.push_back(p->data_);
} }
std::vector<base::Image8UPtr> inputImages; std::vector<base::Image8UPtr> inputImages;
for(int j=4; j<inputNames.size(); j++){ for(int j=5; j<inputNames.size(); j++){
auto iName = inputNames[j]; auto iName = inputNames[j];
auto iptr = std::dynamic_pointer_cast<ios::CameraSrcOut>(interfaces::GetIOPtr(iName)); auto iptr = std::dynamic_pointer_cast<ios::CameraSrcOut>(interfaces::GetIOPtr(iName));
if (iptr == nullptr){
LOG_ERROR << "TraDeS postprocess input image " << iName << " haven't been init or doesn't exist.";
return false;
}
inputImages.push_back(iptr->img_ptr_); inputImages.push_back(iptr->img_ptr_);
} }
...@@ -92,10 +100,10 @@ bool TraDesPostProcess::Exec() { ...@@ -92,10 +100,10 @@ bool TraDesPostProcess::Exec() {
obj->confidence = outputBoxes[b * topK * 6 + i * 6 + 4]; obj->confidence = outputBoxes[b * topK * 6 + i * 6 + 4];
obj->class_label = int(outputBoxes[b * topK * 6 + i * 6 + 5]); obj->class_label = int(outputBoxes[b * topK * 6 + i * 6 + 5]);
obj->class_name = classNames[obj->class_label]; obj->class_name = classNames[obj->class_label];
obj->x1= outputBoxes[b * topK * 6 + i * 6 + 0] / scalex; obj->x1= outputBoxes[b * topK * 6 + i * 6 + 0] * downScale / scalex;
obj->y1 = outputBoxes[b * topK * 6 + i * 6 + 1] / scaley; obj->y1 = outputBoxes[b * topK * 6 + i * 6 + 1] * downScale / scaley;
obj->x2 = outputBoxes[b * topK * 6 + i * 6 + 2] / scalex; obj->x2 = outputBoxes[b * topK * 6 + i * 6 + 2] * downScale/ scalex;
obj->y2 = outputBoxes[b * topK * 6 + i * 6 + 3] / scaley; obj->y2 = outputBoxes[b * topK * 6 + i * 6 + 3] * downScale/ scaley;
obj->image_height = img_height; obj->image_height = img_height;
obj->image_width = img_width; obj->image_width = img_width;
obj->validCoordinate(); // obj->validCoordinate(); //
...@@ -118,115 +126,10 @@ bool TraDesPostProcess::Exec() { ...@@ -118,115 +126,10 @@ bool TraDesPostProcess::Exec() {
}; };
__device__ float Logist(float data){ return 1./(1. + exp(-data)); }
__global__ void trades_postprocess_kernel(const float *hm, const float *reg, const float *wh, const float* seg_weights, const float* seg_feat,
int* output_length, float *output_bboxes, int* output_mask_cnt_lengths, int* output_mask_cnts, const int topK, const int max_cnts_length,
const int w, const int h, const int classes, const int kernel_size, const int seg_dims, const float score_threshold) {
int idx = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x;
if (idx >= w * h * classes) return;
int padding = (kernel_size - 1) / 2;
int offset = -padding;
int stride = w * h;
int grid_x = idx % w;
int grid_y = (idx / w) % h;
int cls = idx / w / h ;
int l, m;
int reg_index = idx - cls * stride;
float c_x, c_y;
// float objProb = Logist(hm[idx]);
float objProb = hm[idx];
if (objProb > score_threshold) {
float max = -1;
int max_index = 0;
for (l = 0; l < kernel_size; ++l){
for (m = 0; m < kernel_size; ++m) {
int cur_x = offset + l + grid_x;
int cur_y = offset + m + grid_y;
int cur_index = cur_y * w + cur_x + stride * cls;
int valid = (cur_x >= 0 && cur_x < w && cur_y >= 0 && cur_y < h);
float val = (valid != 0) ? (hm[cur_index]) : -1;
max_index = (val > max) ? cur_index : max_index;
max = (val > max) ? val : max;
}
}
if(idx == max_index){
int resCount = (int) atomicAdd(output_length, 1);
int newCount = resCount % topK;
// printf("%d: %d, %f ", resCount, idx, max);
if (resCount < topK){ // || det->score < objProb
c_x = grid_x + reg[reg_index];
c_y = grid_y + reg[reg_index + stride];
float boxWidth = pow(Logist(wh[reg_index]), 2) * w;
float boxHeight = pow(Logist(wh[reg_index + stride]), 2) * h;
output_bboxes[newCount * 6 + 0] = (c_x - boxWidth / 2);
output_bboxes[newCount * 6 + 1] = (c_y - boxHeight / 2);
output_bboxes[newCount * 6 + 2] = (c_x + boxWidth / 2);
output_bboxes[newCount * 6 + 3] = (c_y + boxHeight / 2);
output_bboxes[newCount * 6 + 4] = objProb;
output_bboxes[newCount * 6 + 5] = cls;
// get instance mask
int x1 = (int)(c_x - boxWidth / 2), y1 = (int)(c_y - boxHeight / 2);
int x2 = int(ceil(c_x + boxWidth / 2)), y2 = int(ceil(c_y + boxHeight / 2));
x1 = iMAX(x1, 0); y1 = iMAX(y1, 0);
x2 = iMIN(x2, w - 1); y2 = iMIN(y2, h - 1);
bool maskFlag = false, mask_j;
int cnt = 0, num = 0;
int row_left_num = w - (x2 - x1); // w-(x2-x1+1)
cnt = y1 * w + x1;// init with number of zeros
for(int i = y1; i < y2; i++){ // i<=y2
for(int j = x1; j < x2; j++){ // j<=x2
int pos = i * w + j;
float mask_value = 0;
for(int k = 0; k < seg_dims; k++){
mask_value += (seg_weights[k * stride + reg_index] * seg_feat[k * stride + pos]);
}
mask_j = mask_value >= 0;// sigmoid(mask_value) >= 0.5
if(mask_j != maskFlag && num < max_cnts_length){
output_mask_cnts[newCount * max_cnts_length + num] = cnt;
num++;
cnt = 0;
maskFlag = mask_j;
}
cnt++;
}
if(maskFlag && num < max_cnts_length){
output_mask_cnts[newCount * max_cnts_length + num] = cnt;
num++;
cnt = row_left_num;
maskFlag = false;
}else{
cnt += row_left_num;
}
}
output_mask_cnt_lengths[newCount] = num;
}
}
}
}
void TraDesPostProcess::trades_postprocess(const float *hm, const float *reg, const float *wh, const float* seg_weights, const float* seg_feat,
int* output_length, float *output_bboxes, int* output_mask_cnt_lengths, int* output_mask_cnts, const int topK, const int max_cnts_length,
const int w, const int h, const int number_classes, const int kernerl_size, const int seg_dims, const float score_threshold){
uint num = w * h * number_classes;
uint block = 512;
dim3 threads = dim3(block, 1, 1);
trades_postprocess_kernel<<<cudaGridSize(num, block), threads>>>(hm, reg, wh, seg_weights, seg_feat,
output_length, output_bboxes, output_mask_cnt_lengths, output_mask_cnts, topK, max_cnts_length,
w, h, number_classes, kernerl_size, seg_dims, score_threshold);
CUDA_CHECK(cudaDeviceSynchronize());
};
std::string TraDesPostProcess::Name() { std::string TraDesPostProcess::Name() {
return "TraDesPostProcess"; return "TraDesPostProcess";
}; };
DEEPINFER_REGISTER_UNIT(TraDesPostProcess);
} // namespace postprocess } // namespace postprocess
} // namespace deepinfer } // namespace deepinfer
......
...@@ -11,6 +11,7 @@ ...@@ -11,6 +11,7 @@
#include "libs/ios/normal_ios.h" #include "libs/ios/normal_ios.h"
#include "libs/ios/camera_ios.h" #include "libs/ios/camera_ios.h"
#include "libs/ios/detection.h" #include "libs/ios/detection.h"
#include "libs/postprocessors/trades_post_gpu.h"
namespace waytous { namespace waytous {
namespace deepinfer { namespace deepinfer {
...@@ -26,10 +27,6 @@ public: ...@@ -26,10 +27,6 @@ public:
std::string Name() override; std::string Name() override;
protected:
void trades_postprocess(const float *hm, const float *reg, const float *wh, const float* seg_weights, const float* seg_feat,
int* output_length, float *output_bboxes, int* output_mask_cnt_lengths, int* output_mask_cnts, const int topK, const int max_cnts_length,
const int w, const int h, const int number_classes, const int kernerl_size, const int seg_dims, const float score_threshold);
public: public:
base::BlobPtr<int> output_length_ptr; base::BlobPtr<int> output_length_ptr;
...@@ -46,6 +43,8 @@ public: ...@@ -46,6 +43,8 @@ public:
int maxCntsLength = 500; int maxCntsLength = 500;
}; };
DEEPINFER_REGISTER_UNIT(TraDesPostProcess);
} // namespace postprocess } // namespace postprocess
} // namespace deepinfer } // namespace deepinfer
......
#include "libs/postprocessors/trades_post_gpu.h"
namespace waytous {
namespace deepinfer {
namespace postprocess {
__device__ float Logist(float data){ return 1./(1. + exp(-data)); }
__global__ void trades_postprocess_kernel(const float *hm, const float *reg, const float *wh, const float* seg_weights, const float* seg_feat,
int* output_length, float *output_bboxes, int* output_mask_cnt_lengths, int* output_mask_cnts, const int topK, const int max_cnts_length,
const int w, const int h, const int classes, const int kernel_size, const int seg_dims, const float score_threshold) {
int idx = (blockIdx.x + blockIdx.y * gridDim.x) * blockDim.x + threadIdx.x;
if (idx >= w * h * classes) return;
int padding = (kernel_size - 1) / 2;
int offset = -padding;
int stride = w * h;
int grid_x = idx % w;
int grid_y = (idx / w) % h;
int cls = idx / w / h ;
int l, m;
int reg_index = idx - cls * stride;
float c_x, c_y;
// float objProb = Logist(hm[idx]);
float objProb = hm[idx];
if (objProb > score_threshold) {
float max = -1;
int max_index = 0;
for (l = 0; l < kernel_size; ++l){
for (m = 0; m < kernel_size; ++m) {
int cur_x = offset + l + grid_x;
int cur_y = offset + m + grid_y;
int cur_index = cur_y * w + cur_x + stride * cls;
int valid = (cur_x >= 0 && cur_x < w && cur_y >= 0 && cur_y < h);
float val = (valid != 0) ? (hm[cur_index]) : -1;
max_index = (val > max) ? cur_index : max_index;
max = (val > max) ? val : max;
}
}
if(idx == max_index){
int resCount = (int) atomicAdd(output_length, 1);
int newCount = resCount % topK;
// printf("%d: %d, %f ", resCount, idx, max);
if (resCount < topK){ // || det->score < objProb
c_x = grid_x + reg[reg_index];
c_y = grid_y + reg[reg_index + stride];
float boxWidth = pow(Logist(wh[reg_index]), 2) * w;
float boxHeight = pow(Logist(wh[reg_index + stride]), 2) * h;
output_bboxes[newCount * 6 + 0] = (c_x - boxWidth / 2);
output_bboxes[newCount * 6 + 1] = (c_y - boxHeight / 2);
output_bboxes[newCount * 6 + 2] = (c_x + boxWidth / 2);
output_bboxes[newCount * 6 + 3] = (c_y + boxHeight / 2);
output_bboxes[newCount * 6 + 4] = objProb;
output_bboxes[newCount * 6 + 5] = cls;
// get instance mask
int x1 = (int)(c_x - boxWidth / 2), y1 = (int)(c_y - boxHeight / 2);
int x2 = int(ceil(c_x + boxWidth / 2)), y2 = int(ceil(c_y + boxHeight / 2));
x1 = iMAX(x1, 0); y1 = iMAX(y1, 0);
x2 = iMIN(x2, w - 1); y2 = iMIN(y2, h - 1);
bool maskFlag = false, mask_j;
int cnt = 0, num = 0;
int row_left_num = w - (x2 - x1); // w-(x2-x1+1)
cnt = y1 * w + x1;// init with number of zeros
for(int i = y1; i < y2; i++){ // i<=y2
for(int j = x1; j < x2; j++){ // j<=x2
int pos = i * w + j;
float mask_value = 0;
for(int k = 0; k < seg_dims; k++){
mask_value += (seg_weights[k * stride + reg_index] * seg_feat[k * stride + pos]);
}
mask_j = mask_value >= 0;// sigmoid(mask_value) >= 0.5
if(mask_j != maskFlag && num < max_cnts_length){
output_mask_cnts[newCount * max_cnts_length + num] = cnt;
num++;
cnt = 0;
maskFlag = mask_j;
}
cnt++;
}
if(maskFlag && num < max_cnts_length){
output_mask_cnts[newCount * max_cnts_length + num] = cnt;
num++;
cnt = row_left_num;
maskFlag = false;
}else{
cnt += row_left_num;
}
}
output_mask_cnt_lengths[newCount] = num;
}
}
}
}
void trades_postprocess(const float *hm, const float *reg, const float *wh, const float* seg_weights, const float* seg_feat,
int* output_length, float *output_bboxes, int* output_mask_cnt_lengths, int* output_mask_cnts, const int topK, const int max_cnts_length,
const int w, const int h, const int number_classes, const int kernerl_size, const int seg_dims, const float score_threshold){
uint num = w * h * number_classes;
uint block = 512;
dim3 threads = dim3(block, 1, 1);
trades_postprocess_kernel<<<common::cudaGridSize(num, block), threads>>>(hm, reg, wh, seg_weights, seg_feat,
output_length, output_bboxes, output_mask_cnt_lengths, output_mask_cnts, topK, max_cnts_length,
w, h, number_classes, kernerl_size, seg_dims, score_threshold);
CUDA_CHECK(cudaDeviceSynchronize());
};
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#ifndef DEEPINFER_POSTPROCESS_TRDES_GPU_H_
#define DEEPINFER_POSTPROCESS_TRDES_GPU_H_
#include <cuda_runtime.h>
#include <cstdint>
#include "common/common.h"
namespace waytous {
namespace deepinfer {
namespace postprocess {
void trades_postprocess(const float *hm, const float *reg, const float *wh, const float* seg_weights, const float* seg_feat,
int* output_length, float *output_bboxes, int* output_mask_cnt_lengths, int* output_mask_cnts, const int topK, const int max_cnts_length,
const int w, const int h, const int number_classes, const int kernerl_size, const int seg_dims, const float score_threshold);
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#endif
#include "libs/postprocessors/whenet_post.h"
namespace waytous {
namespace deepinfer {
namespace postprocess {
bool WHENetPostProcess::Init(YAML::Node& node, YAML::Node& globalParamNode) {
if(!BaseUnit::Init(node, globalParamNode)){
LOG_WARN << "Init trades postprocess error";
return false;
};
outputYawLength = node["outputYawLength"].as<int>();
outputPitchLength = node["outputPitchLength"].as<int>();
outputRollLength = node["outputRollLength"].as<int>();
return true;
}
bool WHENetPostProcess::Exec(){
std::vector<base::BlobPtr<float>> inputs; // model outputs
for(int i=0; i<inputNames.size(); i++){
auto inputName = inputNames[i];
auto ptr = std::dynamic_pointer_cast<ios::NormalIO>(interfaces::GetIOPtr(inputName));
if (ptr == nullptr){
LOG_ERROR << "WHENet postprocess input " << inputName << " haven't been init or doesn't exist.";
return false;
}
inputs.push_back(ptr->data_);
}
//post
float* yaw = inputs[0]->mutable_cpu_data();
float* roll = inputs[1]->mutable_cpu_data();
float* pitch = inputs[2]->mutable_cpu_data();
auto headpose = std::make_shared<ios::HeadPose>(ios::HeadPose());
interfaces::SetIOPtr(outputNames[0], headpose);
float yawSum = 0, pitchSum=0, rollSum = 0;
// yaw
common::softmax(yaw, outputYawLength);
for(int i=0; i<outputYawLength; i++){
yawSum += yaw[i] * i;
}
yawSum *= 3.0;
yawSum -= 180;
headpose->yaw = yawSum;
// roll
common::softmax(roll, outputRollLength);
for(int i=0; i<outputRollLength; i++){
rollSum += roll[i] * i;
}
rollSum *= 3.0;
rollSum -= 99;
headpose->roll = rollSum;
// pitch
common::softmax(pitch, outputPitchLength);
for(int i=0; i<outputPitchLength; i++){
pitchSum += pitch[i] * i;
}
pitchSum *= 3.0;
pitchSum -= 99;
headpose->pitch = pitchSum;
return true;
}
std::string WHENetPostProcess::Name() {
return "WHENetPostProcess";
};
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#ifndef DEEPINFER_POSTPROCESS_WHENet_H_
#define DEEPINFER_POSTPROCESS_WHENet_H_
#include <cuda_runtime.h>
#include <cstdint>
#include "interfaces/base_unit.h"
#include "base/image.h"
#include "libs/ios/normal_ios.h"
#include "libs/ios/camera_ios.h"
#include "libs/ios/head_pose.h"
namespace waytous {
namespace deepinfer {
namespace postprocess {
class WHENetPostProcess: public interfaces::BaseUnit{
public:
bool Init(YAML::Node& node, YAML::Node& globalParamNode) override;
bool Exec() override;
std::string Name() override;
public:
int outputYawLength;
int outputPitchLength;
int outputRollLength;
};
DEEPINFER_REGISTER_UNIT(WHENetPostProcess);
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#endif
...@@ -14,6 +14,7 @@ bool YoloV5PostProcess::Init(YAML::Node& node, YAML::Node& globalParamNode) { ...@@ -14,6 +14,7 @@ bool YoloV5PostProcess::Init(YAML::Node& node, YAML::Node& globalParamNode) {
truncatedThreshold = node["truncatedThreshold"].as<float>(); // default 5% truncatedThreshold = node["truncatedThreshold"].as<float>(); // default 5%
scoreThreshold = node["scoreThreshold"].as<float>(); scoreThreshold = node["scoreThreshold"].as<float>();
keepTopK = node["keepTopK"].as<int>(); keepTopK = node["keepTopK"].as<int>();
return true;
} }
...@@ -26,6 +27,10 @@ bool YoloV5PostProcess::Exec(){ ...@@ -26,6 +27,10 @@ bool YoloV5PostProcess::Exec(){
for(int i=0; i<4; i++){ for(int i=0; i<4; i++){
auto inputName = inputNames[i]; auto inputName = inputNames[i];
auto ptr = std::dynamic_pointer_cast<ios::NormalIO>(interfaces::GetIOPtr(inputName)); auto ptr = std::dynamic_pointer_cast<ios::NormalIO>(interfaces::GetIOPtr(inputName));
if (ptr == nullptr){
LOG_ERROR << "YoloV5 postprocess input " << inputName << " haven't been init or doesn't exist.";
return false;
}
inputs.push_back(ptr->data_); inputs.push_back(ptr->data_);
} }
...@@ -33,6 +38,10 @@ bool YoloV5PostProcess::Exec(){ ...@@ -33,6 +38,10 @@ bool YoloV5PostProcess::Exec(){
for(int j=4; j<inputNames.size(); j++){ for(int j=4; j<inputNames.size(); j++){
auto iName = inputNames[j]; auto iName = inputNames[j];
auto iptr = std::dynamic_pointer_cast<ios::CameraSrcOut>(interfaces::GetIOPtr(iName)); auto iptr = std::dynamic_pointer_cast<ios::CameraSrcOut>(interfaces::GetIOPtr(iName));
if (iptr == nullptr){
LOG_ERROR << "YoloV5 postprocess input " << iName << " haven't been init or doesn't exist.";
return false;
}
inputImages.push_back(iptr->img_ptr_); inputImages.push_back(iptr->img_ptr_);
} }
...@@ -76,6 +85,7 @@ bool YoloV5PostProcess::Exec(){ ...@@ -76,6 +85,7 @@ bool YoloV5PostProcess::Exec(){
} }
interfaces::SetIOPtr(outName, dets); interfaces::SetIOPtr(outName, dets);
} }
return true;
} }
...@@ -83,7 +93,6 @@ std::string YoloV5PostProcess::Name() { ...@@ -83,7 +93,6 @@ std::string YoloV5PostProcess::Name() {
return "YoloV5PostProcess"; return "YoloV5PostProcess";
}; };
DEEPINFER_REGISTER_UNIT(YoloV5PostProcess);
} // namespace postprocess } // namespace postprocess
} // namespace deepinfer } // namespace deepinfer
......
...@@ -33,6 +33,8 @@ public: ...@@ -33,6 +33,8 @@ public:
}; };
DEEPINFER_REGISTER_UNIT(YoloV5PostProcess);
} // namespace postprocess } // namespace postprocess
} // namespace deepinfer } // namespace deepinfer
......
#include "libs/preprocessors/resize_norm.h" #include "libs/preprocessors/resize_gpu.h"
namespace waytous { namespace waytous {
namespace deepinfer { namespace deepinfer {
namespace preprocess { namespace preprocess {
bool ResizeNorm::Init(YAML::Node& node, YAML::Node& globalParamNode){
if(!BaseUnit::Init(node, globalParamNode)){
LOG_WARN << "Init resize_norm error";
return false;
};
useBGR = node["useBGR"].as<bool>();
std::vector<float> inputMean = node["inputMean"].as<std::vector<float>>();
std::vector<float> inputStd = node["inputStd"].as<std::vector<float>>();
dst.reset(new base::Blob<float>({inferBatchSize, 3, inputHeight, inputWidth}));
auto dst_ptr = std::make_shared<ios::NormalIO>(ios::NormalIO(dst));
interfaces::SetIOPtr(outputNames[0], dst_ptr);
mean.reset(new base::Blob<float>({3, 1}, inputMean.data()));
std.reset(new base::Blob<float>({3, 1}, inputStd.data()));
};
bool ResizeNorm::Exec(){
for(int b=0; b < inputNames.size(); b++){
auto inputName = inputNames[b];
auto input = std::dynamic_pointer_cast<ios::CameraSrcOut>(interfaces::GetIOPtr(inputName));
if(input == nullptr){
LOG_ERROR << "resize norm input ptr haven't init";
return false;
}
auto img = input->img_ptr_;
resizeGPU(
img->mutable_gpu_data(),
img->cols(),
img->rows(),
img->width_step(),
dst->mutable_gpu_data() + (b * 3 * inputHeight * inputWidth), // multi inputs
inputWidth, inputHeight,
mean->mutable_gpu_data(),
std->mutable_gpu_data(),
useBGR, fixAspectRatio, stream_
);
}
// ios::NormalIOPtr dst_ptr = std::make_shared<ios::NormalIO>(ios::NormalIO(dst));
return true;
};
__global__ void warpaffine_kernel( __global__ void warpaffine_kernel(
uint8_t* src, int stepwidth, int src_width, uint8_t* src, int stepwidth, int src_width,
int src_height, float* dst, int dst_width, int src_height, float* dst, int dst_width,
...@@ -138,7 +93,8 @@ __global__ void warpaffine_kernel( ...@@ -138,7 +93,8 @@ __global__ void warpaffine_kernel(
} }
void ResizeNorm::resizeGPU(uint8_t* src, int src_width, int src_height, int step_width,
void resizeGPU(uint8_t* src, int src_width, int src_height, int step_width,
float* dst, int dst_width, int dst_height, float* input_mean, float* input_std, float* dst, int dst_width, int dst_height, float* input_mean, float* input_std,
bool bgr, bool resizeFixAspectRatio, cudaStream_t stream){ bool bgr, bool resizeFixAspectRatio, cudaStream_t stream){
AffineMatrix s2d, d2s; AffineMatrix s2d, d2s;
...@@ -173,17 +129,8 @@ void ResizeNorm::resizeGPU(uint8_t* src, int src_width, int src_height, int step ...@@ -173,17 +129,8 @@ void ResizeNorm::resizeGPU(uint8_t* src, int src_width, int src_height, int step
}; };
std::string ResizeNorm::Name(){
return "ResizeNorm";
};
DEEPINFER_REGISTER_UNIT(ResizeNorm);
} // namespace preprocess } // namespace preprocess
} // namespace deepinfer } // namespace deepinfer
} // namespace waytous } // namespace waytous
#ifndef WAYTOUS_DEEPINFER_PREPROCESSOR_RESIZE_GPU_H_
#define WAYTOUS_DEEPINFER_PREPROCESSOR_RESIZE_GPU_H_
#pragma once
#include <cuda_runtime.h>
#include <cstdint>
#include <opencv2/opencv.hpp>
namespace waytous{
namespace deepinfer{
namespace preprocess{
struct AffineMatrix{
float value[6];
};
void resizeGPU(uint8_t* src, int src_width, int src_height, int step_width,
float* dst, int dst_width, int dst_height, float* input_mean, float* input_std,
bool bgr, bool resizeFixAspectRatio, cudaStream_t stream);
} //namespace preprocess
} //namspace deepinfer
} //namespace waytous
#endif
#include "libs/preprocessors/resize_norm.h"
namespace waytous {
namespace deepinfer {
namespace preprocess {
bool ResizeNorm::Init(YAML::Node& node, YAML::Node& globalParamNode){
if(!BaseUnit::Init(node, globalParamNode)){
LOG_WARN << "Init resize_norm error";
return false;
};
if(inputNames.size() != inferBatchSize){
LOG_ERROR << "Resize norm got wrong inputs number: " << inputNames.size() << " with infer batchsize: " << inferBatchSize;
return false;
}
useBGR = node["useBGR"].as<bool>();
std::vector<float> inputMean = node["inputMean"].as<std::vector<float>>();
std::vector<float> inputStd = node["inputStd"].as<std::vector<float>>();
dst.reset(new base::Blob<float>({inferBatchSize, 3, inputHeight, inputWidth}));
auto dst_ptr = std::make_shared<ios::NormalIO>(ios::NormalIO(dst));
interfaces::SetIOPtr(outputNames[0], dst_ptr);
mean.reset(new base::Blob<float>({3, 1}, inputMean.data()));
mean->mutable_gpu_data();
std.reset(new base::Blob<float>({3, 1}, inputStd.data()));
std->mutable_gpu_data();
return true;
};
bool ResizeNorm::Exec(){
for(int b=0; b < inputNames.size(); b++){
auto inputName = inputNames[b];
auto input = std::dynamic_pointer_cast<ios::CameraSrcOut>(interfaces::GetIOPtr(inputName));
if(input == nullptr){
LOG_ERROR << "resize norm input" << inputName << " haven't init";
return false;
}
auto img = input->img_ptr_;
resizeGPU(
img->mutable_gpu_data(),
img->cols(),
img->rows(),
img->width_step(),
dst->mutable_gpu_data() + (b * 3 * inputHeight * inputWidth), // multi inputs
inputWidth, inputHeight,
mean->mutable_gpu_data(),
std->mutable_gpu_data(),
useBGR, fixAspectRatio, stream_
);
}
// ios::NormalIOPtr dst_ptr = std::make_shared<ios::NormalIO>(ios::NormalIO(dst));
return true;
};
std::string ResizeNorm::Name(){
return "ResizeNorm";
};
} // namespace preprocess
} // namespace deepinfer
} // namespace waytous
...@@ -10,16 +10,13 @@ ...@@ -10,16 +10,13 @@
#include "libs/sources/camera_src.h" #include "libs/sources/camera_src.h"
#include "libs/ios/normal_ios.h" #include "libs/ios/normal_ios.h"
#include "libs/ios/camera_ios.h" #include "libs/ios/camera_ios.h"
#include "libs/preprocessors/resize_gpu.h"
namespace waytous { namespace waytous {
namespace deepinfer { namespace deepinfer {
namespace preprocess { namespace preprocess {
struct AffineMatrix{
float value[6];
};
class ResizeNorm: public interfaces::BaseUnit{ class ResizeNorm: public interfaces::BaseUnit{
...@@ -30,11 +27,6 @@ public: ...@@ -30,11 +27,6 @@ public:
std::string Name() override; std::string Name() override;
protected:
void resizeGPU(uint8_t* src, int src_width, int src_height, int step_width,
float* dst, int dst_width, int dst_height, float* input_mean, float* input_std,
bool bgr, bool resizeFixAspectRatio, cudaStream_t stream);
public: public:
cudaStream_t stream_; cudaStream_t stream_;
base::BlobPtr<float> dst, mean, std; base::BlobPtr<float> dst, mean, std;
...@@ -42,6 +34,8 @@ public: ...@@ -42,6 +34,8 @@ public:
}; };
DEEPINFER_REGISTER_UNIT(ResizeNorm);
} // namespace preprocess } // namespace preprocess
} // namespace deepinfer } // namespace deepinfer
} // namespace waytous } // namespace waytous
......
#include "libs/preprocessors/undistort.h"
namespace waytous {
namespace deepinfer {
namespace preprocess {
bool Undistort::Init(YAML::Node& node, YAML::Node& globalParamNode) {
if(!BaseUnit::Init(node, globalParamNode)){
LOG_WARN << "Init trades postprocess error";
return false;
};
width_ = node["imageWidth"].as<int>();
height_ = node["imageHeight"].as<int>();
std::string IntrinsicPath, ExtrinsicPath = "";
IntrinsicPath = node["IntrinsicPath"].as<std::string>();
if(node["ExtrinsicPath"].IsDefined() && !node["ExtrinsicPath"].IsNull()){
ExtrinsicPath = node["ExtrinsicPath"].as<std::string>();
}
if(!loadIntrinsic(IntrinsicPath)){
LOG_WARN << "Load intrinsic error: " << IntrinsicPath;
return false;
}
if(ExtrinsicPath != "" && !loadExtrinsics(ExtrinsicPath)){
LOG_WARN << "Load Extrinsic error: " << ExtrinsicPath;
return false;
}
d_mapx_.Reshape({height_, width_});
d_mapy_.Reshape({height_, width_});
Eigen::Matrix3f I;
I << 1.f, 0.f, 0.f, 0.f, 1.f, 0.f, 0.f, 0.f, 1.f;
InitUndistortRectifyMap(camera_intrinsic,
distortion_coefficients, I,
camera_intrinsic, width_,
height_, &d_mapx_, &d_mapy_);
inited_ = true;
return true;
}
bool Undistort::loadExtrinsics(std::string& yaml_file){
std::string yaml_path = common::GetAbsolutePath(common::ConfigRoot::GetRootPath(), yaml_file);
if (!common::PathExists(yaml_path)) {
LOG_INFO << yaml_path << " does not exist!";
return false;
}
YAML::Node node = YAML::LoadFile(yaml_path);
double qw = 0.0;
double qx = 0.0;
double qy = 0.0;
double qz = 0.0;
double tx = 0.0;
double ty = 0.0;
double tz = 0.0;
try {
if (node.IsNull()) {
LOG_INFO << "Load " << yaml_path << " failed! please check!";
return false;
}
qw = node["transform"]["rotation"]["w"].as<double>();
qx = node["transform"]["rotation"]["x"].as<double>();
qy = node["transform"]["rotation"]["y"].as<double>();
qz = node["transform"]["rotation"]["z"].as<double>();
tx = node["transform"]["translation"]["x"].as<double>();
ty = node["transform"]["translation"]["y"].as<double>();
tz = node["transform"]["translation"]["z"].as<double>();
} catch (YAML::InvalidNode &in) {
LOG_ERROR << "load camera extrisic file " << yaml_path
<< " with error, YAML::InvalidNode exception";
return false;
} catch (YAML::TypedBadConversion<double> &bc) {
LOG_ERROR << "load camera extrisic file " << yaml_path
<< " with error, YAML::TypedBadConversion exception";
return false;
} catch (YAML::Exception &e) {
LOG_ERROR << "load camera extrisic file " << yaml_path
<< " with error, YAML exception:" << e.what();
return false;
}
camera_extrinsic.setConstant(0);
Eigen::Quaterniond q;
q.x() = qx;
q.y() = qy;
q.z() = qz;
q.w() = qw;
camera_extrinsic.block<3, 3>(0, 0) = q.normalized().toRotationMatrix();
camera_extrinsic(0, 3) = tx;
camera_extrinsic(1, 3) = ty;
camera_extrinsic(2, 3) = tz;
camera_extrinsic(3, 3) = 1;
return true;
}
bool Undistort::loadIntrinsic(std::string& yaml_file){
std::string yaml_path = common::GetAbsolutePath(common::ConfigRoot::GetRootPath(), yaml_file);
if (!common::PathExists(yaml_path)) {
LOG_INFO << yaml_path << " does not exist!";
return false;
}
YAML::Node node = YAML::LoadFile(yaml_path);
if (node.IsNull()) {
LOG_INFO << "Load " << yaml_path << " failed! please check!";
return false;
}
try{
if(node["image_width"].IsDefined() && !node["image_width"].IsNull()){
int width = node["image_width"].as<int>();
if(width_ != width){
LOG_INFO << "image width from cameraInfoConfig (" << width_<< ") and intrinsic (" << width << ") does not match, set with the intrinsic width. ";
width_ = width;
}
}
if(node["image_height"].IsDefined() && !node["image_height"].IsNull()){
int height = node["image_height"].as<int>();
if(height_ != height){
LOG_INFO << "image height from cameraInfoConfig (" << height_<< ") and intrinsic (" << height << ") does not match, set with the intrinsic height. ";
height_ = height;
}
}
for(int i=0; i<9; i++){
camera_intrinsic(i) = node["camera_matrix"]["data"][i].as<float>();
}
for(int i=0; i<5; i++){
distortion_coefficients(i) = node["distortion_coefficients"]["data"][i].as<float>();
}
if(node["rectification_matrix"].IsDefined() && node["rectification_matrix"]["data"].IsDefined() &&
!node["rectification_matrix"]["data"].IsNull()
){
for(int i=0; i<9; i++){
camera_rectification(i) = node["rectification_matrix"]["data"][i].as<float>();
}
}
if(node["projection_matrix"].IsDefined() && node["projection_matrix"]["data"].IsDefined() &&
!node["projection_matrix"]["data"].IsNull()
){
for(int i=0; i<12; i++){
camera_projection(i) = node["projection_matrix"]["data"][i].as<float>();
}
}
} catch (YAML::Exception &e) {
LOG_ERROR << "load camera params file " << yaml_path
<< " with error, YAML exception: " << e.what();
return false;
}
return true;
}
void Undistort::InitUndistortRectifyMap(
const Eigen::Matrix3f &camera_model,
const Eigen::Matrix<float, 1, 5>& distortion, const Eigen::Matrix3f &R,
const Eigen::Matrix3f &new_camera_model, int width, int height,
base::Blob<float> *d_mapx, base::Blob<float> *d_mapy) {
float fx = camera_model(0, 0);
float fy = camera_model(1, 1);
float cx = camera_model(0, 2);
float cy = camera_model(1, 2);
float nfx = new_camera_model(0, 0);
float nfy = new_camera_model(1, 1);
float ncx = new_camera_model(0, 2);
float ncy = new_camera_model(1, 2);
float k1 = distortion(0, 0);
float k2 = distortion(0, 1);
float p1 = distortion(0, 2);
float p2 = distortion(0, 3);
float k3 = distortion(0, 4);
Eigen::Matrix3f Rinv = R.inverse();
for (int v = 0; v < height_; ++v) {
float *x_ptr = d_mapx->mutable_cpu_data() + d_mapx->offset(v);
float *y_ptr = d_mapy->mutable_cpu_data() + d_mapy->offset(v);
for (int u = 0; u < width_; ++u) {
Eigen::Matrix<float, 3, 1> xy1;
xy1 << (static_cast<float>(u) - ncx) / nfx,
(static_cast<float>(v) - ncy) / nfy, 1;
auto XYW = Rinv * xy1;
double nx = XYW(0, 0) / XYW(2, 0);
double ny = XYW(1, 0) / XYW(2, 0);
double r_square = nx * nx + ny * ny;
double scale = (1 + r_square * (k1 + r_square * (k2 + r_square * k3)));
double nnx =
nx * scale + 2 * p1 * nx * ny + p2 * (r_square + 2 * nx * nx);
double nny =
ny * scale + p1 * (r_square + 2 * ny * ny) + 2 * p2 * nx * ny;
x_ptr[u] = static_cast<float>(nnx * fx + cx);
y_ptr[u] = static_cast<float>(nny * fy + cy);
}
}
}
bool Undistort::Exec(){
auto iptr = std::dynamic_pointer_cast<ios::CameraSrcOut>(interfaces::GetIOPtr(inputNames[0]));
if (iptr == nullptr){
LOG_ERROR << "Undistort input " << inputNames[0] << " haven't been init or doesn't exist.";
return false;
}
if (!inited_) {
LOG_WARN << "Undistortion not init.";
return false;
}
auto src_img = iptr->img_ptr_;
auto dst_img = std::make_shared<base::Image8U>(base::Image8U(src_img->rows(), src_img->cols(), src_img->type()));
auto output = std::make_shared<ios::CameraSrcOut>(ios::CameraSrcOut(dst_img));
NppiInterpolationMode remap_mode = NPPI_INTER_LINEAR;
NppiSize image_size;
image_size.width = width_;
image_size.height = height_;
NppiRect remap_roi = {0, 0, width_, height_};
NppStatus status;
int d_map_step = static_cast<int>(d_mapx_.shape(1) * sizeof(float));
switch (src_img->channels()) {
case 1:
status = nppiRemap_8u_C1R(
src_img->gpu_data(), image_size, src_img->width_step(), remap_roi,
d_mapx_.gpu_data(), d_map_step, d_mapy_.gpu_data(), d_map_step,
dst_img->mutable_gpu_data(), dst_img->width_step(), image_size,
remap_mode);
break;
case 3:
status = nppiRemap_8u_C3R(
src_img->gpu_data(), image_size, src_img->width_step(), remap_roi,
d_mapx_.gpu_data(), d_map_step, d_mapy_.gpu_data(), d_map_step,
dst_img->mutable_gpu_data(), dst_img->width_step(), image_size,
remap_mode);
break;
default:
LOG_ERROR << "Invalid number of channels: " << src_img->channels();
return false;
}
if (status != NPP_SUCCESS) {
LOG_ERROR << "NPP_CHECK_NPP - status = " << status;
return false;
}
interfaces::SetIOPtr(outputNames[0], output);
return true;
}
std::string Undistort::Name() {
return "Undistort";
};
} // namespace postprocess
} // namespace deepinfer
} // namespace waytous
#ifndef DEEPINFER_PREPROCESS_UNDISTORT_H_
#define DEEPINFER_PREPROCESS_UNDISTORT_H_
#include <memory>
#include <string>
#include <algorithm>
#include <Eigen/Dense>
#include <npp.h>
#include "common/file.h"
#include "interfaces/base_unit.h"
#include "base/image.h"
#include "libs/ios/camera_ios.h"
namespace waytous {
namespace deepinfer {
namespace preprocess {
class Undistort: public interfaces::BaseUnit{
public:
bool Init(YAML::Node& node, YAML::Node& globalParamNode) override;
bool Exec() override;
std::string Name() override;
bool loadIntrinsic(std::string& yaml_file);
bool loadExtrinsics(std::string& yaml_file);
void InitUndistortRectifyMap(const Eigen::Matrix3f &camera_model,
const Eigen::Matrix<float, 1, 5> &distortion,
const Eigen::Matrix3f &R,
const Eigen::Matrix3f &new_camera_model,
int width, int height, base::Blob<float> *d_mapx,
base::Blob<float> *d_mapy);
public:
base::Blob<float> d_mapx_;
base::Blob<float> d_mapy_;
Eigen::Matrix<double, 4, 4, Eigen::RowMajor> camera_extrinsic; // load by another yaml file
Eigen::Matrix<float, 3, 3, Eigen::RowMajor> camera_intrinsic;
Eigen::Matrix<float, 3, 3, Eigen::RowMajor> camera_rectification;
Eigen::Matrix<float, 3, 4, Eigen::RowMajor> camera_projection;
Eigen::Matrix<float, 1, 5, Eigen::RowMajor> distortion_coefficients;
int width_ = 0; // image cols
int height_ = 0; // image rows
int in_size_ = 0; // size of the input image in byte
int out_size_ = 0; // size of the output image in byte
int device_ = 0; // device number for gpu
bool inited_ = 0;
};
DEEPINFER_REGISTER_UNIT(Undistort);
} // namespace preprocess
} // namespace deepinfer
} // namespace waytous
#endif
...@@ -9,6 +9,10 @@ namespace sources { ...@@ -9,6 +9,10 @@ namespace sources {
bool CameraSrc::Exec(){ bool CameraSrc::Exec(){
auto src_input = interfaces::GetIOPtr(inputNames[0]); auto src_input = interfaces::GetIOPtr(inputNames[0]);
if(src_input == nullptr){
LOG_ERROR << "CameraSrc input" << inputNames[0] << " haven't init";
return false;
}
auto src = std::dynamic_pointer_cast<ios::CameraSrcIn>(src_input); auto src = std::dynamic_pointer_cast<ios::CameraSrcIn>(src_input);
auto img = std::make_shared<base::Image8U>(base::Image8U(src->cv_img_)); auto img = std::make_shared<base::Image8U>(base::Image8U(src->cv_img_));
auto dst = std::make_shared<ios::CameraSrcOut>(ios::CameraSrcOut(img)); auto dst = std::make_shared<ios::CameraSrcOut>(ios::CameraSrcOut(img));
...@@ -21,7 +25,6 @@ std::string CameraSrc::Name(){ ...@@ -21,7 +25,6 @@ std::string CameraSrc::Name(){
return "CameraSrc"; return "CameraSrc";
} }
DEEPINFER_REGISTER_UNIT(CameraSrc);
} // namespace sources } // namespace sources
......
...@@ -25,6 +25,8 @@ public: ...@@ -25,6 +25,8 @@ public:
}; };
using CameraSrcPtr = std::shared_ptr<CameraSrc>; using CameraSrcPtr = std::shared_ptr<CameraSrc>;
DEEPINFER_REGISTER_UNIT(CameraSrc);
} // namespace sources } // namespace sources
} // namespace deepinfer } // namespace deepinfer
......
...@@ -9,6 +9,10 @@ namespace tracker{ ...@@ -9,6 +9,10 @@ namespace tracker{
bool ByteTracker::Init(YAML::Node& node, YAML::Node& globalParamNode) bool ByteTracker::Init(YAML::Node& node, YAML::Node& globalParamNode)
{ {
if(!BaseUnit::Init(node, globalParamNode)){
LOG_WARN << "Init resize_norm error";
return false;
};
int frame_rate = node["frame_rate"].as<int>(); int frame_rate = node["frame_rate"].as<int>();
int track_buffer = node["track_buffer"].as<int>(); int track_buffer = node["track_buffer"].as<int>();
track_thresh = node["track_thresh"].as<float>(); track_thresh = node["track_thresh"].as<float>();
...@@ -25,7 +29,12 @@ bool ByteTracker::Init(YAML::Node& node, YAML::Node& globalParamNode) ...@@ -25,7 +29,12 @@ bool ByteTracker::Init(YAML::Node& node, YAML::Node& globalParamNode)
bool ByteTracker::Exec() bool ByteTracker::Exec()
{ {
auto objects = std::dynamic_pointer_cast<ios::Detection2Ds>(interfaces::GetIOPtr(inputNames[0]))->detections; if(interfaces::GetIOPtr(inputNames[0]) == nullptr){
LOG_ERROR << "ByteTracker input" << inputNames[0] << " haven't init";
return false;
}
auto input = std::dynamic_pointer_cast<ios::Detection2Ds>(interfaces::GetIOPtr(inputNames[0]));
auto objects = input->detections;
////////////////// Step 1: Get detections ////////////////// ////////////////// Step 1: Get detections //////////////////
this->frame_id++; this->frame_id++;
...@@ -673,7 +682,6 @@ std::string ByteTracker::Name() { ...@@ -673,7 +682,6 @@ std::string ByteTracker::Name() {
}; };
DEEPINFER_REGISTER_UNIT(ByteTracker);
} //namespace tracker } //namespace tracker
} //namspace deepinfer } //namspace deepinfer
......
...@@ -52,6 +52,8 @@ private: ...@@ -52,6 +52,8 @@ private:
KalmanFilter kalman_filter; KalmanFilter kalman_filter;
}; };
DEEPINFER_REGISTER_UNIT(ByteTracker);
} //namespace tracker } //namespace tracker
} //namspace deepinfer } //namspace deepinfer
} //namespace waytous } //namespace waytous
......
...@@ -17,8 +17,8 @@ bool CameraModel::Init(std::string& configPath) { ...@@ -17,8 +17,8 @@ bool CameraModel::Init(std::string& configPath) {
LOG_WARN << "Load " << configPath << " failed! please check!"; LOG_WARN << "Load " << configPath << " failed! please check!";
return false; return false;
} }
inputNames = modelConfigNode.as<std::vector<std::string>>("inputNames"); inputNames = modelConfigNode["inputNames"].as<std::vector<std::string>>();
outputNames = modelConfigNode.as<std::vector<std::string>>("outputNames"); outputNames = modelConfigNode["outputNames"].as<std::vector<std::string>>();
auto globalParamNode = modelConfigNode["globalParams"]; auto globalParamNode = modelConfigNode["globalParams"];
// units // units
...@@ -26,7 +26,9 @@ bool CameraModel::Init(std::string& configPath) { ...@@ -26,7 +26,9 @@ bool CameraModel::Init(std::string& configPath) {
for(int i=0; i<unitNodes.size(); i++){ for(int i=0; i<unitNodes.size(); i++){
auto unitNode = unitNodes[i]; auto unitNode = unitNodes[i];
std::string unitName = unitNode["name"].as<std::string>(); std::string unitName = unitNode["name"].as<std::string>();
interfaces::BaseUnitPtr unitPtr = std::make_shared<interfaces::BaseUnit>(interfaces::BaseUnitRegisterer::GetInstanceByName(unitName)); LOG_INFO << "Init unit: " << unitName;
interfaces::BaseUnitPtr unitPtr;
unitPtr.reset(interfaces::BaseUnitRegisterer::GetInstanceByName(unitName));
if(!unitPtr->Init(unitNode, globalParamNode)){ if(!unitPtr->Init(unitNode, globalParamNode)){
LOG_WARN << "Init unit " << unitName << " failed!"; LOG_WARN << "Init unit " << unitName << " failed!";
return false; return false;
...@@ -42,16 +44,22 @@ bool CameraModel::Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::Bas ...@@ -42,16 +44,22 @@ bool CameraModel::Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::Bas
for (int i=0; i<inputs.size(); i++){ for (int i=0; i<inputs.size(); i++){
auto input_img = inputs[i]; auto input_img = inputs[i];
auto inputName = inputNames[i]; auto inputName = inputNames[i];
LOG_INFO << "input: " << inputName;
auto input = std::make_shared<ios::CameraSrcIn>(ios::CameraSrcIn(input_img)); auto input = std::make_shared<ios::CameraSrcIn>(ios::CameraSrcIn(input_img));
interfaces::SetIOPtr(inputName, input); interfaces::SetIOPtr(inputName, input);
} }
// infer // infer
for(auto unit: units_){ for(auto unit: units_){
unit->Exec(); LOG_INFO << "exec unit: " << unit->Name();
if(!unit->Exec()){
LOG_ERROR << unit->Name() << " unit exec error";
return false;
};
} }
// output // output
for(auto outName: outputNames){ for(auto outName: outputNames){
LOG_INFO << "output: " << outName;
outputs.push_back(interfaces::GetIOPtr(outName)); outputs.push_back(interfaces::GetIOPtr(outName));
} }
...@@ -85,7 +93,6 @@ std::string CameraModel::Name(){ ...@@ -85,7 +93,6 @@ std::string CameraModel::Name(){
} }
DEEPINFER_REGISTER_MODELS(CameraModel);
} // namespace camera } // namespace camera
} // namespace deepinfer } // namespace deepinfer
......
...@@ -28,6 +28,7 @@ public: ...@@ -28,6 +28,7 @@ public:
std::vector<interfaces::BaseUnitPtr> units_; std::vector<interfaces::BaseUnitPtr> units_;
}; };
DEEPINFER_REGISTER_MODELS(CameraModel);
} // namespace camera } // namespace camera
} // namespace deepinfer } // namespace deepinfer
......
#include "tasks/task_bsw.h"
namespace waytous{
namespace deepinfer{
namespace task{
bool TaskBSW::Init(std::string& taskConfigPath){
if(!interfaces::BaseTask::Init(taskConfigPath)){
LOG_ERROR << "Init task detect error";
return false;
};
std::string detectorName = taskNode["detectorName"].as<std::string>();
std::string detectorConfigPath = taskNode["detectorConfigPath"].as<std::string>();
detector.reset(interfaces::BaseModelRegisterer::GetInstanceByName(detectorName));
if(!detector->Init(detectorConfigPath)){
LOG_ERROR << detectorName << " detector init problem";
return false;
};
imageWidth = taskNode["imageWidth"].as<int>();
imageHeight = taskNode["imageHeight"].as<int>();
mask = cv::Mat::zeros(imageHeight, imageWidth, CV_8UC3);
// init distance pools
std::string warningDistancePoolsPath = taskNode["warningDistancePoolsPath"].as<std::string>();
std::string distanceConfigPath = common::GetAbsolutePath(common::ConfigRoot::GetRootPath(), warningDistancePoolsPath);
if(!common::PathExists(distanceConfigPath)){
LOG_ERROR << "camera distance pool config_file " << distanceConfigPath << " not exist.";
return false;
}
YAML::Node distanceNode = YAML::LoadFile(distanceConfigPath);
if (distanceNode.IsNull()) {
LOG_ERROR << "Load " << distanceConfigPath << " failed! please check!";
return false;
}
// init ranges
std::string warningRangeConfigPath = taskNode["warningRangeConfigPath"].as<std::string>();
if(!InitRanges(warningRangeConfigPath, distanceNode)){
LOG_ERROR << "Init BSW warning range error.";
return false;
}
return true;
}
bool TaskBSW::Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs){
if(inputs.size() != 1){
LOG_ERROR << 'Now only support infer one image once.';
return false;
}
std::vector<interfaces::BaseIOPtr> dets;
if(!detector->Exec(inputs, dets)){
LOG_ERROR << "Task Detect Exec error";
return false;
};
auto objs = std::dynamic_pointer_cast<ios::Detection2Ds>(dets[0])->detections;
// delete lost tracklets
for(auto& bo_pair: BSWRes){
auto bo = bo_pair.second;
bool matched = false;
for(auto& obj: objs){
if(bo->obj->track_id == obj->track_id){
matched = true;
break;
}
}
if(!matched){
bo->lost_ages += 1;
if(bo->lost_ages > 10){
BSWRes.erase(bo_pair.first);
}
}
}
for(auto &obj : objs){
auto k = BSWRes.find(obj->track_id);
if(k == BSWRes.end()){
BSWRes[obj->track_id] = std::make_shared<BSWResult>(BSWResult());
BSWRes[obj->track_id]->counters = std::vector<int>(ranges.size(), 0);
}
auto& bo = BSWRes[obj->track_id];
bo->obj = obj;
// if(obj->class_name != "person") continue;
float buttom_cx = (obj->x1 + obj->x2) / 2;
float buttom_cy = obj->y2;
bool isIn = false;
for(int i = ranges.size() - 1; i >=0; i--){ // start from the worst warning.
if(isIn){
bo->counters[i] += 1;
continue;
}
isIn = isInRange(ranges[i].polygan, buttom_cx, buttom_cy);
if(isIn){
bo->counters[i] += 1;
if(bo->counters[i] > ranges[i].warningFrameThreshold){
bo->msg = WarningName2Msg[ranges[i].name];
}
}else{
bo->counters[i] = 0;
}
}
outputs.push_back(bo);
}
return true;
}
void TaskBSW::Visualize(cv::Mat* image, interfaces::BaseIOPtr outs){
for(auto &bo_pair : BSWRes){
auto& bo = bo_pair.second;
if(bo->lost_ages > 0){
continue;
}
auto &obj = bo->obj;
cv::Scalar color = bo->counters[0] % 4 == 0 ? cv::Scalar(255, 255, 255) : ranges[(int) bo->msg].color;
cv::rectangle(*image, cv::Rect(int(obj->x1), int(obj->y1), int(obj->x2 - obj->x1), int(obj->x2 - obj->y1)), color, 2);
cv::putText(*image, std::to_string(obj->track_id) + "." + obj->class_name + ":" + common::formatValue(obj->confidence, 2),
cv::Point(int(obj->x1), int(obj->y1) - 5), cv::FONT_HERSHEY_SIMPLEX, 0.5, color, 1);
}
// draw outlines
cv::addWeighted(*image, 0.9, mask, 0.1, 0, *image);
// // draw warning
// cv::putText(image, r.name, cv::Point(100, 100), cv::FONT_HERSHEY_SIMPLEX, 1, r.color, 1);
}
bool TaskBSW::InitRanges(const std::string& warningRangeConfigPath, YAML::Node& distanceNode){
std::string configPath = common::GetAbsolutePath(common::ConfigRoot::GetRootPath(), warningRangeConfigPath);
if(!common::PathExists(configPath)){
LOG_ERROR << "blind area config_file " << configPath << " not exist.";
return false;
}
YAML::Node rangeNode = YAML::LoadFile(configPath);
if (rangeNode.IsNull()) {
LOG_ERROR << "Load " << configPath << " failed! please check!";
return false;
}
bool useFullPolygan = taskNode["useFullPolygan"].as<bool>();
auto infoNode = rangeNode["warningInfos"];
for(int i=0; i < infoNode.size(); i++){
RangeInfo rinfo;
auto curNode = infoNode[i];
rinfo.name = curNode["name"].as<std::string>();
auto color = curNode["color"].as<std::vector<int>>();
rinfo.color = cv::Scalar(color[0], color[1], color[2]);
rinfo.warningFrameThreshold = curNode["warningFrameThreshold"].as<int>();
float distance = curNode["distance"].as<float>();
std::vector<int> point;
if(distance > 0){
std::string distanceNameInNode = "dist_" + std::to_string(int(distance * 100)); // meter->centermeter
auto polygonNode = distanceNode[distanceNameInNode];
if(!polygonNode.IsDefined()){
LOG_ERROR << rinfo.name << ", camera distance " << distance << " m, cannot find in pool.";
return false;
}
// LOG_INFO << rinfo.name << " " << rinfo.warningFrameThreshold;
for(int j=0; j < polygonNode.size(); j++){
point = polygonNode[j].as<std::vector<int>>();
if(!useFullPolygan && j == 0){
if(point[0] < imageHeight - point[1]){
rinfo.polygan.push_back(cv::Point(0, imageHeight));// fisrt left-buttom
rinfo.polygan.push_back(cv::Point(0, point[1])); // second left-top
}else{
rinfo.polygan.push_back(cv::Point(point[0], imageHeight)); // only left-buttom
}
}
if(imageWidth - point[0] <= 1){ // 1919->1920
point[0] = imageWidth;
}
if(imageHeight - point[1] <= 1){ // 1079->1080
point[1] = imageHeight;
}
rinfo.polygan.push_back(cv::Point(point[0], point[1]));
}
if(!useFullPolygan){
if(imageWidth - point[0] < imageHeight - point[1]){
rinfo.polygan.push_back(cv::Point(imageWidth, point[1]));
rinfo.polygan.push_back(cv::Point(imageWidth, imageHeight));
}else{
rinfo.polygan.push_back(cv::Point(point[0], imageHeight));
}
}
}else{
// distance < 0, if means distance = inf, set polygan with the image's outline.
rinfo.polygan.push_back(cv::Point(0, imageHeight));
rinfo.polygan.push_back(cv::Point(0, 0));
rinfo.polygan.push_back(cv::Point(imageWidth, 0));
rinfo.polygan.push_back(cv::Point(imageWidth, imageHeight));
}
cv::fillPoly(mask, rinfo.polygan, rinfo.color);
ranges.push_back(rinfo);
}
return true;
};
bool TaskBSW::isInRange(const std::vector<cv::Point>& polygan, float x, float y){
bool isIn = false;
int j = polygan.size() - 1;
for(int i=0; i < polygan.size(); i++ ){
auto& pi = polygan[i];
auto& pj = polygan[j];
if((pi.y < y && pj.y >= y || pj.y < y && pi.y >= y) &&
(pi.x <= x || pj.x <= x)){
isIn ^= (pi.x + (y - pi.y) / (pj.y - pi.y + 1e-5) * (pj.x - pi.x) < x);
}
j = i;
}
return isIn;
}
std::string TaskBSW::Name(){
return "TaskBSW";
}
} //namespace task
} //namspace deepinfer
} //namespace waytous
#ifndef WAYTOUS_DEEPINFER_TASK_BSW_H_
#define WAYTOUS_DEEPINFER_TASK_BSW_H_
#include "interfaces/base_task.h"
#include "models/camera_model.h"
#include "libs/ios/detection.h"
namespace waytous{
namespace deepinfer{
namespace task{
struct RangeInfo{
std::string name;
cv::Scalar color;
int warningFrameThreshold;
std::vector<cv::Point> polygan;
};
enum class BSWMsg{ // blind spot warning
BSW_NORMAL = 0,
BSW_YELLOW = 1,
BSW_RED = 2,
};
class BSWResult: public interfaces::BaseIO{
public:
ios::Det2DPtr obj;
std::vector<int> counters; // for count warning frame
int lost_ages = 0; // untracked frame number
BSWMsg msg = BSWMsg::BSW_NORMAL;
};
using BSWResultPtr = std::shared_ptr<BSWResult>;
class TaskBSW: public interfaces::BaseTask{
public:
std::map<std::string, BSWMsg> WarningName2Msg = {
{"Green", BSWMsg::BSW_NORMAL},
{"Yellow", BSWMsg::BSW_YELLOW},
{"Red", BSWMsg::BSW_RED},
};
bool Init(std::string& taskConfigPath) override;
bool Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs) override;
void Visualize(cv::Mat* image, interfaces::BaseIOPtr outs) override;
std::string Name() override;
private:
bool InitRanges(const std::string& warningRangeConfigPath, YAML::Node& distanceNode);
bool isInRange(const std::vector<cv::Point>& polygan, float x, float y);
public:
std::shared_ptr<interfaces::BaseModel> detector;
std::vector<RangeInfo> ranges;
std::map<int, BSWResultPtr> BSWRes;
int imageWidth, imageHeight;
cv::Mat mask;
};
DEEPINFER_REGISTER_TASKS(TaskBSW);
} //namespace task
} //namspace deepinfer
} //namespace waytous
#endif
...@@ -19,22 +19,28 @@ bool TaskDetect::Init(std::string& taskConfigPath){ ...@@ -19,22 +19,28 @@ bool TaskDetect::Init(std::string& taskConfigPath){
LOG_ERROR << detectorName << " detector init problem"; LOG_ERROR << detectorName << " detector init problem";
return false; return false;
}; };
return true;
} }
bool TaskDetect::Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs){ bool TaskDetect::Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs){
detector->Exec(inputs, outputs); if(!detector->Exec(inputs, outputs)){
LOG_ERROR << "Task Detect Exec error";
return false;
};
return true;
} }
void TaskDetect::Visualize(cv::Mat* image, interfaces::BaseIOPtr outs){ void TaskDetect::Visualize(cv::Mat* image, interfaces::BaseIOPtr outs){
auto detections = std::dynamic_pointer_cast<ios::Detection2Ds>(outs)->detections; auto detections = std::dynamic_pointer_cast<ios::Detection2Ds>(outs)->detections;
for(auto &obj : detections){ for(auto &obj : detections){
// LOG_INFO << "box: " << obj->x1 << " " << obj->x2 << " " << obj->y1 << " " << obj->y2;
cv::Scalar color = get_color(obj->class_label); cv::Scalar color = get_color(obj->class_label);
cv::rectangle(*image, cv::Rect(obj->x1, obj->y1, obj->x2 - obj->x1, obj->y2 - obj->y1), color, 2); cv::rectangle(*image, cv::Rect(int(obj->x1), int(obj->y1), int(obj->x2 - obj->x1), int(obj->y2 - obj->y1)), color, 2);
cv::putText(*image, common::formatValue(obj->confidence, 2) + ":" + cv::putText(*image, common::formatValue(obj->confidence, 2) + ":" +
std::to_string(obj->track_id) + "." + obj->class_name, std::to_string(obj->track_id) + "." + obj->class_name,
cv::Point(obj->x1, obj->y1 - 5), cv::FONT_HERSHEY_SIMPLEX, 0.5, color, 1); cv::Point(int(obj->x1), int(obj->y1) - 5), cv::FONT_HERSHEY_SIMPLEX, 0.5, color, 1);
} }
} }
...@@ -43,7 +49,6 @@ std::string TaskDetect::Name(){ ...@@ -43,7 +49,6 @@ std::string TaskDetect::Name(){
return "TaskDetect"; return "TaskDetect";
} }
DEEPINFER_REGISTER_TASKS(TaskDetect);
} //namespace task } //namespace task
} //namspace deepinfer } //namspace deepinfer
......
...@@ -21,10 +21,12 @@ public: ...@@ -21,10 +21,12 @@ public:
std::string Name() override; std::string Name() override;
public: public:
std::shared_ptr<camera::CameraModel> detector; std::shared_ptr<interfaces::BaseModel> detector;
}; };
DEEPINFER_REGISTER_TASKS(TaskDetect);
} //namespace task } //namespace task
} //namspace deepinfer } //namspace deepinfer
} //namespace waytous } //namespace waytous
......
#include "tasks/task_dms.h"
namespace waytous{
namespace deepinfer{
namespace task{
bool TaskDMS::Init(std::string& taskConfigPath){
if(!interfaces::BaseTask::Init(taskConfigPath)){
LOG_ERROR << "Init task detect error";
return false;
};
std::string faceDetectorName = taskNode["faceDetectorName"].as<std::string>();
std::string faceDetectorConfigPath = taskNode["faceDetectorConfigPath"].as<std::string>();
std::string landmarkDetectorName = taskNode["landmarkDetectorName"].as<std::string>();
std::string landmarkDetectorConfigPath = taskNode["landmarkDetectorConfigPath"].as<std::string>();
std::string headposeDetectorName = taskNode["headposeDetectorName"].as<std::string>();
std::string headposeDetectorConfigPath = taskNode["headposeDetectorConfigPath"].as<std::string>();
mouthARThreshold = taskNode["mouthARThreshold"].as<float>();
eyeARThreshold = taskNode["eyeARThreshold"].as<float>();
eyeARConsecFrames = taskNode["eyeARConsecFrames"].as<int>();
distractionConsecFrames = taskNode["distractionConsecFrames"].as<int>();
unmaskedConsecFrames = taskNode["unmaskedConsecFrames"].as<int>();
nodriverConsecFrames = taskNode["nodriverConsecFrames"].as<int>();
sightYawThresholdLeft = taskNode["sightYawThresholdLeft"].as<int>();
sightYawThresholdRight = taskNode["sightYawThresholdRight"].as<int>();
sightPitchThresholdLeft = taskNode["sightPitchThresholdLeft"].as<int>();
sightPitchThresholdRight = taskNode["sightPitchThresholdRight"].as<int>();
faceDetector.reset(interfaces::BaseModelRegisterer::GetInstanceByName(faceDetectorName));
if(!faceDetector->Init(faceDetectorConfigPath)){
LOG_ERROR << faceDetectorName << " faceDetector init problem";
return false;
};
landmarkDetector.reset(interfaces::BaseModelRegisterer::GetInstanceByName(landmarkDetectorName));
if(!landmarkDetector->Init(landmarkDetectorConfigPath)){
LOG_ERROR << landmarkDetectorName << " face landmarks detector init problem";
return false;
};
headposeDetector.reset(interfaces::BaseModelRegisterer::GetInstanceByName(headposeDetectorName));
if(!headposeDetector->Init(headposeDetectorConfigPath)){
LOG_ERROR << headposeDetectorName << " face headpose detector init problem";
return false;
};
res = std::make_shared<DMSResult>(DMSResult());
return true;
}
bool TaskDMS::Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs){
if(inputs.size() != 1){
LOG_ERROR << 'Now only support infer one image once.';
return false;
}
std::vector<interfaces::BaseIOPtr> faceDets;
if(!faceDetector->Exec(inputs, faceDets)){
LOG_ERROR << "Task DMS face detector Exec error";
return false;
};
outputs.push_back(res);
auto faces = std::dynamic_pointer_cast<ios::Detection2Ds>(faceDets[0])->detections;
// driver
if(faces.size() < 1){
NODRIVER_COUNTER++;
if(NODRIVER_COUNTER >= nodriverConsecFrames){
res->msg = DMSMsg::DMS_NODRIVER;
LOG_INFO << "No driver!";
}else
res->msg = DMSMsg::DMS_NONE;
return true;
}
NODRIVER_COUNTER = 0; // reinit nodriver counter
auto faceObj = faces[0]; // only get the best face to analyse
res->faceBBox = faceObj;
// mask
if(faceObj->class_label == 1){
UNMASKED_COUNTER = 0;
}else if (faceObj->class_label == 0){// driver didnot wear mask
UNMASKED_COUNTER++;
if(UNMASKED_COUNTER >= unmaskedConsecFrames){
res->msg = DMSMsg::DMS_UNMASK; // TODO
}
}
// scale box 1.2, to square
int image_height = inputs[0]->rows;
int image_width = inputs[0]->cols;
int boxWidth = faceObj->x2 - faceObj->x1 + 1;
int boxHeight = faceObj->y2 - faceObj->y1 + 1;
int boxSquareSize = (int)std::min(boxWidth * 1.2, boxHeight * 1.2);
int boxSquareX1 = faceObj->x1 + boxWidth / 2 - boxSquareSize / 2;
int boxSquareX2 = boxSquareX1 + boxSquareSize;
int boxSquareY1 = faceObj->y1 + boxHeight / 2 - boxSquareSize / 2;
int boxSquareY2 = boxSquareY1 + boxSquareSize;
// clip
boxSquareX1 = std::max(0, boxSquareX1);
boxSquareY1 = std::max(0, boxSquareY1);
boxSquareX2 = std::min(image_width, boxSquareX2);
boxSquareY2 = std::min(image_height, boxSquareY2);
auto faceROI = cv::Rect2i(boxSquareX1, boxSquareY1, boxSquareX2 - boxSquareX1, boxSquareY2 - boxSquareY1);
res->faceSquare = faceROI;
// set landmarks and whenet input src
std::vector<cv::Mat*> subInputs;
auto faceImage = (*inputs[0])(faceROI);
subInputs.push_back(&faceImage);
// face landmarks
std::vector<interfaces::BaseIOPtr> landmarks_vec;
if(!landmarkDetector->Exec(subInputs, landmarks_vec)){
LOG_ERROR << "face landmarks detect doesnot end normally!";
return false;
};
res->face_landmarks = std::dynamic_pointer_cast<ios::Landmarks>(landmarks_vec[0]);
for(auto& m: res->face_landmarks->landmarks){
m->x += res->faceSquare.x;
m->y += res->faceSquare.y;
}
// eyes
eyeAR = (accOrganAspectRatio(eyeLandmarkIndices[0]) + accOrganAspectRatio(eyeLandmarkIndices[1])) / 2.0;
if(eyeAR < eyeARThreshold){
EYE_CLOSE_COUNTER++;
if(EYE_CLOSE_COUNTER >= eyeARConsecFrames){
res->msg = DMSMsg::DMS_NOD_EYE;
}
}else{
EYE_CLOSE_COUNTER = 0;
}
// mouth
mouthAR = accOrganAspectRatio(mouthLandmarkIndices);
if(mouthAR > mouthARThreshold){
res->msg = DMSMsg::DMS_NOD_MOUTH;
}
// headpose
std::vector<interfaces::BaseIOPtr> headpose_vec;
if(!headposeDetector->Exec(subInputs, headpose_vec)){
LOG_ERROR << "face headpose detect doesnot end normally!";
return false;
};
res->headPose = std::dynamic_pointer_cast<ios::HeadPose>(headpose_vec[0]);
// sight
if(res->headPose->yaw < sightYawThresholdLeft | res->headPose->yaw > sightYawThresholdRight |
res->headPose->pitch < sightPitchThresholdLeft | res->headPose->pitch > sightPitchThresholdRight){
DISTRACTION_COUNTER++;
if(DISTRACTION_COUNTER >= distractionConsecFrames){
res->msg = DMSMsg::DMS_INATTENTION;
}
}else{
DISTRACTION_COUNTER = 0;
}
return true;
}
void TaskDMS::Visualize(cv::Mat* image, interfaces::BaseIOPtr outs){
switch(res->msg){
case DMSMsg::DMS_NODRIVER:
cv::putText(*image, "NODRIVER!", cv::Point(0, 20), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(255, 0, 0), 1, cv::LINE_AA);
break;
case DMSMsg::DMS_UNMASK:
cv::putText(*image, "UNMASKED!", cv::Point(0, 40), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(255, 0, 0), 1, cv::LINE_AA);
break;
case DMSMsg::DMS_NOD_EYE:
cv::putText(*image, "WARNING: DROWSINESS ALERT BY EYE!", cv::Point(10, 60), cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 255), 1);
break;
case DMSMsg::DMS_NOD_MOUTH:
cv::putText(*image, "WARNING: DROWSINESS ALERT BY MOUTH!", cv::Point(10, 80), cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 255), 1);
break;
case DMSMsg::DMS_INATTENTION:
cv::putText(*image, "WARNING: DISTRACTION ALERT!", cv::Point(10, 100), cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 255, 255), 1);
break;
}
if(NODRIVER_COUNTER == 0){
cv::rectangle(*image, res->faceSquare, cv::Scalar(0, 0, 255), 2);
cv::putText(*image, res->faceBBox->class_name + ":" + common::formatValue(res->faceBBox->confidence, 2),
cv::Point(res->faceSquare.x, res->faceSquare.y), cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(255, 0, 255), 1);
cv::putText(*image, "eyeCount:" + std::to_string(EYE_CLOSE_COUNTER) + "/" + std::to_string(eyeARConsecFrames), cv::Point(10, 120),
cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(255, 255, 0), 1);
cv::putText(*image, "distrCount:" + std::to_string(DISTRACTION_COUNTER) + "/" + std::to_string(distractionConsecFrames), cv::Point(10, 140),
cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(255, 255, 0), 1);
cv::putText(*image, "unmaskCount:" + std::to_string(UNMASKED_COUNTER) + "/" + std::to_string(unmaskedConsecFrames), cv::Point(10, 160),
cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(255, 255, 0), 1);
cv::putText(*image, "nodriverCount:" + std::to_string(NODRIVER_COUNTER) + "/" + std::to_string(nodriverConsecFrames), cv::Point(10, 180),
cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(255, 255, 0), 1);
cv::putText(*image, "EAR: " + common::formatValue(eyeAR, 2), cv::Point(400, 20), cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 255), 1);
cv::putText(*image, "MAR: " + common::formatValue(mouthAR, 2), cv::Point(400, 40), cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 255), 1);
cv::putText(*image, "yaw: " + common::formatValue(res->headPose->yaw, 2), cv::Point(res->faceSquare.x, res->faceSquare.y + res->faceSquare.height),
cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(100, 255, 0), 1);
cv::putText(*image, "pitch: " + common::formatValue(res->headPose->pitch, 2), cv::Point(res->faceSquare.x, res->faceSquare.y + res->faceSquare.height - 15),
cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(100, 255, 0), 1);
cv::putText(*image, "roll: " + common::formatValue(res->headPose->roll, 2), cv::Point(res->faceSquare.x, res->faceSquare.y + res->faceSquare.height - 30),
cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(100, 255, 0), 1);
for(auto& point: res->face_landmarks->landmarks){
cv::circle(*image, cv::Point(point->x, point->y), 2, cv::Scalar(0, 255, 0), -1);
}
drawAxis(*image, res->headPose->pitch, res->headPose->yaw, res->headPose->roll,
res->faceSquare.x + res->faceSquare.width / 2, res->faceSquare.y + res->faceSquare.height / 2,
res->faceSquare.width / 2);
}
}
float TaskDMS::accOrganAspectRatio(int* indices){
float A = common::euclidean(res->face_landmarks->landmarks[indices[1]]->x, res->face_landmarks->landmarks[indices[1]]->y,
res->face_landmarks->landmarks[indices[5]]->x, res->face_landmarks->landmarks[indices[5]]->y);
float B = common::euclidean(res->face_landmarks->landmarks[indices[2]]->x, res->face_landmarks->landmarks[indices[2]]->y,
res->face_landmarks->landmarks[indices[4]]->x, res->face_landmarks->landmarks[indices[4]]->y);
float C = common::euclidean(res->face_landmarks->landmarks[indices[0]]->x, res->face_landmarks->landmarks[indices[0]]->y,
res->face_landmarks->landmarks[indices[3]]->x, res->face_landmarks->landmarks[indices[3]]->y);
return (A + B) / (2.0 * C);
}
void TaskDMS::resetCounter(){
EYE_CLOSE_COUNTER = 0;
DISTRACTION_COUNTER = 0;
UNMASKED_COUNTER = 0;
NODRIVER_COUNTER = 0;
}
void TaskDMS::drawAxis(cv::Mat& img, float& pitch_, float& yaw_, float& roll_, int cx, int cy, int size){
float pitch = pitch_ * PI / 180.;
float yaw = -yaw_ * PI / 180.;
float roll = roll_ * PI / 180.;
// X-Axis pointing to right. drawn in red
float x1 = size * (std::cos(yaw) * std::cos(roll)) + cx;
float y1 = size * (std::cos(pitch) * std::sin(roll) + std::cos(roll) * std::sin(pitch) * std::sin(yaw)) + cy;
// Y-Axis | drawn in green
// v
float x2 = size * (-std::cos(yaw) * std::sin(roll)) + cx;
float y2 = size * (std::cos(pitch) * std::cos(roll) - std::sin(pitch) * std::sin(yaw) * std::sin(roll)) + cy;
// Z-Axis (out of the screen) drawn in blue
float x3 = size * (std::sin(yaw)) + cx;
float y3 = size * (-std::cos(yaw) * std::sin(pitch)) + cy;
cv::line(img, cv::Point(cx, cy), cv::Point(int(x1), int(y1)), cv::Scalar(0,0,255), 2);
cv::line(img, cv::Point(cx, cy), cv::Point(int(x2), int(y2)), cv::Scalar(0,255,0), 2);
cv::line(img, cv::Point(cx, cy), cv::Point(int(x3), int(y3)), cv::Scalar(255,0,0), 2);
}
std::string TaskDMS::Name(){
return "TaskDMS";
}
} //namespace task
} //namspace deepinfer
} //namespace waytous
#ifndef WAYTOUS_DEEPINFER_TASK_DMS_H_
#define WAYTOUS_DEEPINFER_TASK_DMS_H_
#include "interfaces/base_task.h"
#include "models/camera_model.h"
#include "libs/ios/detection.h"
#include "libs/ios/head_pose.h"
#include "libs/ios/landmark.h"
namespace waytous{
namespace deepinfer{
namespace task{
enum class DMSMsg{
DMS_NONE = 0, // 正常
DMS_NOD = 10, // 打瞌睡(闭眼/打哈欠)
DMS_NOD_EYE = 11,
DMS_NOD_MOUTH = 12,
DMS_CALL = 20, // 打电话
DMS_INATTENTION = 30, // 注意力不集中(抬头/低头/左顾右盼)
DMS_NODRIVER = 40, // 司机不在
DMS_UNMASK = 50 // 未带口罩
};
class DMSResult: public interfaces::BaseIO{
public:
ios::Det2DPtr faceBBox;
cv::Rect2i faceSquare;
ios::HeadPosePtr headPose;
ios::LandmarksPtr face_landmarks;
DMSMsg msg = DMSMsg::DMS_NONE;
};
using DMSResultPtr = std::shared_ptr<DMSResult>;
class TaskDMS: public interfaces::BaseTask{
public:
bool Init(std::string& taskConfigPath) override;
bool Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs) override;
void Visualize(cv::Mat* image, interfaces::BaseIOPtr outs) override;
std::string Name() override;
private:
float accOrganAspectRatio(int* indices);
void resetCounter();
void drawAxis(cv::Mat& img, float& pitch_, float& yaw_, float& roll_, int cx, int cy, int size);
public:
std::shared_ptr<interfaces::BaseModel> faceDetector;
std::shared_ptr<interfaces::BaseModel> landmarkDetector;
std::shared_ptr<interfaces::BaseModel> headposeDetector;
int eyeLandmarkIndices[2][6] = {{36, 37, 38, 39, 40, 41}, {42, 43, 44, 45, 46, 47}}; // eye indices: left and right
int mouthLandmarkIndices[6] = {48, 48 + 2, 48 + 4, 48 + 6, 48 + 8, 48 + 10};//mouth indicies from 48 to 68, but interested 6 points
float mouthARThreshold = 0.75; //嘴巴横纵比的阈值
float eyeARThreshold = 0.25; //眼睛横纵比的阈值
int eyeARConsecFrames = 15; //触发警报,即眼睛横纵比低于阈值的连续帧数阈值
int distractionConsecFrames = 1;
int unmaskedConsecFrames = 20;
int nodriverConsecFrames = 20;
int sightYawThresholdLeft = -40;//degree
int sightYawThresholdRight = 40;//degree
int sightPitchThresholdLeft = -40;//degree
int sightPitchThresholdRight = 40;//degree
// DMS counters
int EYE_CLOSE_COUNTER = 0; //眼睛横纵比低于阈值的连续帧数计数
int DISTRACTION_COUNTER = 0;
int UNMASKED_COUNTER = 0;
int NODRIVER_COUNTER = 0;
float eyeAR;
float mouthAR;
DMSResultPtr res;
};
DEEPINFER_REGISTER_TASKS(TaskDMS);
} //namespace task
} //namspace deepinfer
} //namespace waytous
#endif
#include "tasks/task_fusion.h"
namespace waytous{
namespace deepinfer{
namespace task{
bool TaskFusion::Init(std::string& taskConfigPath){
if(!interfaces::BaseTask::Init(taskConfigPath)){
LOG_ERROR << "Init task detect error";
return false;
};
std::string detectorName = taskNode["detectorName"].as<std::string>();
std::string detectorConfigPath = taskNode["detectorConfigPath"].as<std::string>();
model.reset(interfaces::BaseModelRegisterer::GetInstanceByName(detectorName));
if(!model->Init(detectorConfigPath)){
LOG_ERROR << detectorName << " detector init problem";
return false;
};
return true;
}
bool TaskFusion::Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs){
if(!model->Exec(inputs, outputs)){
LOG_ERROR << "Task Detect Exec error";
return false;
};
return true;
}
void TaskFusion::Visualize(cv::Mat* image, interfaces::BaseIOPtr outs){
auto detections = std::dynamic_pointer_cast<ios::Detection2Ds>(outs)->detections;
for(auto &obj : detections){
// LOG_INFO << "box: " << obj->x1 << " " << obj->x2 << " " << obj->y1 << " " << obj->y2;
cv::Scalar color = get_color(obj->class_label);
cv::rectangle(*image, cv::Rect(int(obj->x1), int(obj->y1), int(obj->x2 - obj->x1), int(obj->y2 - obj->y1)), color, 2);
cv::putText(*image, common::formatValue(obj->confidence, 2) + ":" +
std::to_string(obj->track_id) + "." + obj->class_name,
cv::Point(int(obj->x1), int(obj->y1) - 5), cv::FONT_HERSHEY_SIMPLEX, 0.5, color, 1);
}
}
std::string TaskFusion::Name(){
return "TaskFusion";
}
} //namespace task
} //namspace deepinfer
} //namespace waytous
#ifndef WAYTOUS_DEEPINFER_TASK_FUSION_H_
#define WAYTOUS_DEEPINFER_TASK_FUSION_H_
#include "interfaces/base_task.h"
#include "models/camera_model.h"
#include "libs/ios/detection.h"
namespace waytous{
namespace deepinfer{
namespace task{
class TaskFusion: public interfaces::BaseTask{
public:
bool Init(std::string& taskConfigPath) override;
bool Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs) override;
void Visualize(cv::Mat* image, interfaces::BaseIOPtr outs) override;
std::string Name() override;
public:
std::shared_ptr<interfaces::BaseModel> model;
};
DEEPINFER_REGISTER_TASKS(TaskFusion);
} //namespace task
} //namspace deepinfer
} //namespace waytous
#endif
#include "tasks/task_mots.h"
namespace waytous{
namespace deepinfer{
namespace task{
bool TaskMOTS::Init(std::string& taskConfigPath){
if(!interfaces::BaseTask::Init(taskConfigPath)){
LOG_ERROR << "Init task detect error";
return false;
};
std::string segmentorName = taskNode["segmentorName"].as<std::string>();
std::string segmentorConfigPath = taskNode["segmentorConfigPath"].as<std::string>();
segmentor.reset(interfaces::BaseModelRegisterer::GetInstanceByName(segmentorName));
if(!segmentor->Init(segmentorConfigPath)){
LOG_ERROR << segmentorName << " segmentor init problem";
return false;
};
return true;
}
bool TaskMOTS::Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs){
if(!segmentor->Exec(inputs, outputs)){
LOG_ERROR << "Task Detect Exec error";
return false;
};
return true;
}
void TaskMOTS::Visualize(cv::Mat* image, interfaces::BaseIOPtr outs){
auto detections = std::dynamic_pointer_cast<ios::Detection2Ds>(outs)->detections;
cv::Mat realInstanceMask, colorInstance;
for(auto& obj: detections){
cv::Scalar color = get_color(obj->class_label * 100 + obj->track_id);
cv::putText(*image, std::to_string(obj->track_id) + ":" + common::formatValue(obj->confidence, 2),
cv::Point(int(obj->x1), int(obj->y1) - 5),
0, 0.6, cv::Scalar(0, 0, 255), 2, cv::LINE_AA);
cv::rectangle(*image, cv::Rect(int(obj->x1), int(obj->y1),
int(obj->x2 - obj->x1), int(obj->y2 - obj->y1)), color, 2);
// LOG_INFO << obj->mask_ptr->width << ", " << obj->mask_ptr->height << ", " << obj->mask_ptr->rle_string;
cv::Mat instance_mask = obj->mask_ptr->decode();
instance_mask.convertTo(instance_mask, CV_32FC1);
cv::resize(instance_mask, realInstanceMask, image->size());
(*image).copyTo(colorInstance);
for(int i=0; i<realInstanceMask.rows; i++){
for(int j=0; j<realInstanceMask.cols; j++){
if(realInstanceMask.at<float>(i, j) >= 0.5){
colorInstance.at<cv::Vec3b>(i, j) = cv::Vec3b(color[0], color[1], color[2]);
}
}
}
cv::addWeighted(*image, 0.5, colorInstance, 0.5, 0, *image);
}
}
std::string TaskMOTS::Name(){
return "TaskMOTS";
}
} //namespace task
} //namspace deepinfer
} //namespace waytous
#ifndef WAYTOUS_DEEPINFER_TASK_MOTS_H_
#define WAYTOUS_DEEPINFER_TASK_MOTS_H_
#include "interfaces/base_task.h"
#include "models/camera_model.h"
#include "libs/ios/detection.h"
namespace waytous{
namespace deepinfer{
namespace task{
class TaskMOTS: public interfaces::BaseTask{
public:
bool Init(std::string& taskConfigPath) override;
bool Exec(std::vector<cv::Mat*> inputs, std::vector<interfaces::BaseIOPtr>& outputs) override;
void Visualize(cv::Mat* image, interfaces::BaseIOPtr outs) override;
std::string Name() override;
public:
std::shared_ptr<interfaces::BaseModel> segmentor; // contains tracker
};
DEEPINFER_REGISTER_TASKS(TaskMOTS);
} //namespace task
} //namspace deepinfer
} //namespace waytous
#endif
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment