29 Commits

Author SHA1 Message Date
AiYangSky
f9c32a3754 Fixed a bug caused by abnormal timestamps in the ROS environment
Signed-off-by: AiYangSky <1732570904@qq.com>
2024-04-11 07:52:39 +00:00
jario
4a9adf7f98 fix Eigen/Dense: No such file err 2024-04-02 12:02:12 +08:00
jario
97ae2aa6c2 fix byte error 2024-04-02 11:50:15 +08:00
jario-jin
a1262883c5 !37 fix bugs in x86-intel.
Merge pull request !37 from Daniel/lxm
2024-02-29 08:16:33 +00:00
Daniel
29a2d9abf5 fix bugs in x86-intel. 2024-02-21 10:08:57 +08:00
Daniel
21cabc3ed7 fix bugs in x86-intel. 2024-02-21 10:04:56 +08:00
jario
f346ad49d9 fix model_sync 2024-02-02 23:26:16 +08:00
jario
29702bfd11 fix camera cannot open continuously 2024-02-02 23:16:49 +08:00
jario
b52645c3a6 fix 2024-01-27 11:07:42 +08:00
jario
83bf2f9656 fix model sync 2024-01-19 23:56:05 +08:00
jario
9c4d8a400c fix 2024-01-19 22:55:31 +08:00
jario
212c9f18fa fix model manager with various batchsize 2024-01-19 21:12:13 +08:00
jario
334c2055d9 fix 2024-01-17 11:35:41 +08:00
jario-jin
5108de8df4 model manager v1.0 & add model_sync.py 2024-01-17 11:00:54 +08:00
jario-jin
62708c742c !36 model-manager-v1
Merge pull request !36 from jario-jin/model-manager
2024-01-12 14:06:24 +00:00
jario-jin
a2621bf4dd fix Intel platform installation script 2024-01-12 22:03:05 +08:00
jario
f06151c7a0 finish model manager v1 2024-01-12 21:58:08 +08:00
jario-jin
4a2cf609c4 update video_io/sv_video_input.cpp.
Signed-off-by: jario-jin <jariof@foxmail.com>
2024-01-05 12:26:47 +00:00
jario
9612f9fe83 fix bug when used as lib 2024-01-02 14:02:34 +08:00
jario
cc715bef70 add MJPG 2024-01-01 15:03:31 +08:00
jario
4e7762631d fix bugs 2024-01-01 11:44:48 +08:00
Your Name
7a5012bd31 fix 2024-01-01 11:18:37 +08:00
jario-jin
c556994c45 !35 add video save and stream in intel hw by ffmpeg
Merge pull request !35 from Daniel/intel_vaapi
2024-01-01 02:33:33 +00:00
jario-jin
e98063b4e0 !34 add openVINO algorithm implementation
Merge pull request !34 from Daniel/lxm
2024-01-01 02:32:51 +00:00
Your Name
aa0e15c457 upd install scripts 2024-01-01 10:11:37 +08:00
Daniel
f2f273d99d add intel vaapi function 2023-12-29 18:04:44 +08:00
Daniel
9b770f3c8b add openVINO algorithm implementation 2023-12-28 17:54:55 +08:00
jario
819fd4c82a optim MIPI reading 2023-12-27 18:42:25 +08:00
jario-jin
cf6a285f3e fix video reading skipping 2023-12-27 15:24:47 +08:00
97 changed files with 3611 additions and 227 deletions

12
.gitignore vendored
View File

@@ -1,6 +1,13 @@
# Distribution / packaging
.Python
build/
models/
confs/
ZLM/
ZLMediaKit/
ffmpeg-4.2.5/
nv-codec-headers/
*.bz2
develop-eggs/
dist/
eggs/
@@ -15,6 +22,11 @@ share/python-wheels/
*.egg
MANIFEST
.idea/
calib_webcam_1280x720.yaml
calib_webcam_640x480.yaml
sv_algorithm_params.json
sv_algorithm_params_coco_1280.json
sv_algorithm_params_coco_640.json
# Prerequisites
*.d

View File

@@ -24,6 +24,7 @@ else()
option(USE_FFMPEG "BUILD WITH FFMPEG." ON)
elseif(PLATFORM STREQUAL "X86_INTEL")
add_definitions(-DPLATFORM_X86_INTEL)
option(USE_INTEL "BUILD WITH INTEL." ON)
option(USE_FFMPEG "BUILD WITH FFMPEG." ON)
else()
message(FATAL_ERROR "UNSUPPORTED PLATFORM!")
@@ -38,6 +39,10 @@ if(USE_CUDA)
message(STATUS "CUDA: ON")
endif()
if(USE_INTEL)
add_definitions(-DWITH_INTEL)
message(STATUS "INTEL: ON")
endif()
if(USE_GSTREAMER)
add_definitions(-DWITH_GSTREAMER)
@@ -72,6 +77,9 @@ include_directories(
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src/GX40
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl/driver/src
${CMAKE_CURRENT_SOURCE_DIR}/gimbal_ctrl
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/common_det/intel
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/landing_det/intel
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/veri/intel
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/common_det/cuda
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/landing_det/cuda
${CMAKE_CURRENT_SOURCE_DIR}/algorithm/sot/ocv470
@@ -187,7 +195,23 @@ if(USE_CUDA)
list(APPEND spirecv_SRCS ${ALG_SRC_FILES})
endif()
if(USE_INTEL)
file(GLOB ALG_SRC_FILES ${CMAKE_CURRENT_SOURCE_DIR}/algorithm/common_det/intel/*.cpp)
list(APPEND spirecv_SRCS ${ALG_SRC_FILES})
file(GLOB ALG_SRC_FILES ${CMAKE_CURRENT_SOURCE_DIR}/algorithm/landing_det/intel/*.cpp)
list(APPEND spirecv_SRCS ${ALG_SRC_FILES})
file(GLOB ALG_SRC_FILES ${CMAKE_CURRENT_SOURCE_DIR}/algorithm/veri/intel/*.cpp)
list(APPEND spirecv_SRCS ${ALG_SRC_FILES})
endif()
if(USE_FFMPEG)
if(USE_INTEL)
file(GLOB ALG_SRC_FILES ${CMAKE_CURRENT_SOURCE_DIR}/video_io/ffmpeg/x86_intel/*.cpp)
list(APPEND spirecv_SRCS ${ALG_SRC_FILES})
elseif(USE_CUDA)
file(GLOB ALG_SRC_FILES ${CMAKE_CURRENT_SOURCE_DIR}/video_io/ffmpeg/x86_cuda/*.cpp)
list(APPEND spirecv_SRCS ${ALG_SRC_FILES})
endif()
file(GLOB ALG_SRC_FILES ${CMAKE_CURRENT_SOURCE_DIR}/video_io/ffmpeg/*.cpp)
list(APPEND spirecv_SRCS ${ALG_SRC_FILES})
endif()
@@ -231,10 +255,22 @@ if(USE_CUDA) # PLATFORM_X86_CUDA & PLATFORM_JETSON
target_link_libraries(SpireCVSeg sv_world)
elseif(PLATFORM STREQUAL "X86_INTEL") # Links to Intel-OpenVINO libraries here
# Intel-Openvino
include_directories(
PUBLIC /opt/intel/openvino_2022/runtime/include/
PUBLIC /opt/intel/openvino_2022/runtime/include/ie/
)
link_directories(
${InferenceEngine_LIBRARIES}
/opt/intel/openvino_2022/runtime/lib/intel64/libopenvino.so
)
add_library(sv_world SHARED ${spirecv_SRCS})
target_link_libraries(
sv_world ${OpenCV_LIBS}
sv_gimbal
${InferenceEngine_LIBRARIES}
/opt/intel/openvino_2022/runtime/lib/intel64/libopenvino.so
)
endif()
@@ -328,12 +364,14 @@ if(PLATFORM STREQUAL "JETSON")
file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/build/${PROJECT_NAME}Config.cmake.in [[
@PACKAGE_INIT@
find_package(OpenCV 4 REQUIRED)
find_package(Eigen3 REQUIRED)
link_directories(/usr/local/cuda/lib64)
set(SV_INCLUDE_DIRS
@SV_INSTALL_PREFIX@/include
/usr/include/x86_64-linux-gnu
/usr/local/cuda/include
${OpenCV_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
/usr/include/gstreamer-1.0
/usr/local/include/gstreamer-1.0
/usr/include/glib-2.0
@@ -352,6 +390,7 @@ elseif(PLATFORM STREQUAL "X86_CUDA")
file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/build/${PROJECT_NAME}Config.cmake.in [[
@PACKAGE_INIT@
find_package(OpenCV 4 REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(fmt REQUIRED)
link_directories(/usr/local/cuda/lib64)
set(SV_INCLUDE_DIRS
@@ -359,6 +398,7 @@ set(SV_INCLUDE_DIRS
/usr/include/x86_64-linux-gnu
/usr/local/cuda/include
${OpenCV_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
)
set(SV_LIBRARIES
@SV_INSTALL_PREFIX@/lib/libsv_yoloplugins.so
@@ -373,11 +413,13 @@ elseif(PLATFORM STREQUAL "X86_INTEL")
file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/build/${PROJECT_NAME}Config.cmake.in [[
@PACKAGE_INIT@
find_package(OpenCV 4 REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(fmt REQUIRED)
set(SV_INCLUDE_DIRS
@SV_INSTALL_PREFIX@/include
/usr/include/x86_64-linux-gnu
${OpenCV_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
)
set(SV_LIBRARIES
@SV_INSTALL_PREFIX@/lib/libsv_world.so

View File

@@ -38,9 +38,9 @@ SpireCV is an **real-time edge perception SDK** built for **intelligent unmanned
- **Platform level**
- [x] X86 + Nvidia GPUs (10 series, 20 series, and 30 series graphics cards recommended)
- [x] Jetson (AGX Orin/Xavier、Orin NX/Nano、Xavier NX)
- [ ] Intel CPU (coming soon)
- [ ] Rockchip (coming soon)
- [x] Intel CPU
- [ ] HUAWEI Ascend (coming soon)
- [ ] Rockchip (coming soon)
## Demos
- **QR code detection**

View File

@@ -38,9 +38,9 @@ SpireCV是一个专为**智能无人系统**打造的**边缘实时感知SDK**
- **平台层**
- [x] X86+Nvidia GPU推荐10系、20系、30系显卡
- [x] JetsonAGX Orin/Xavier、Orin NX/Nano、Xavier NX
- [ ] Intel CPU(推进中)
- [ ] Rockchip推进中
- [x] Intel CPU
- [ ] HUAWEI Ascend推进中
- [ ] Rockchip推进中
## 功能展示
- **二维码检测**

View File

@@ -1,6 +1,8 @@
#include "common_det_cuda_impl.h"
#include <cmath>
#include <fstream>
#include <iostream>
#include "sv_util.h"
#define SV_MODEL_DIR "/SpireCV/models/"
#define SV_ROOT_DIR "/SpireCV/"
@@ -362,17 +364,51 @@ bool CommonObjectDetectorCUDAImpl::cudaSetup(CommonObjectDetectorBase* base_, bo
bool with_segmentation = base_->withSegmentation();
double thrs_conf = base_->getThrsConf();
double thrs_nms = base_->getThrsNms();
std::string model = base_->getModel();
int bs = base_->getBatchSize();
char bs_c[8];
sprintf(bs_c, "%d", bs);
std::string bs_s(bs_c);
std::string engine_fn = get_home() + SV_MODEL_DIR + dataset + ".engine";
std::vector<std::string> files;
_list_dir(get_home() + SV_MODEL_DIR, files, "-online.engine", "Nv-" + dataset + "-yolov5" + model + "_b" + bs_s + "_c");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
engine_fn = get_home() + SV_MODEL_DIR + files[0];
}
if (input_w == 1280)
{
engine_fn = get_home() + SV_MODEL_DIR + dataset + "_HD.engine";
files.clear();
_list_dir(get_home() + SV_MODEL_DIR, files, "-online.engine", "Nv-" + dataset + "-yolov5" + model + "6_b" + bs_s + "_c");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
engine_fn = get_home() + SV_MODEL_DIR + files[0];
}
else
{
engine_fn = get_home() + SV_MODEL_DIR + dataset + "_HD.engine";
}
}
if (with_segmentation)
{
base_->setInputH(640);
base_->setInputW(640);
engine_fn = get_home() + SV_MODEL_DIR + dataset + "_SEG.engine";
files.clear();
_list_dir(get_home() + SV_MODEL_DIR, files, "-online.engine", "Nv-" + dataset + "-yolov5" + model + "_seg_b" + bs_s + "_c");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
engine_fn = get_home() + SV_MODEL_DIR + files[0];
}
else
{
engine_fn = get_home() + SV_MODEL_DIR + dataset + "_SEG.engine";
}
}
std::cout << "Load: " << engine_fn << std::endl;
if (!is_file_exist(engine_fn))
@@ -414,17 +450,5 @@ bool CommonObjectDetectorCUDAImpl::cudaSetup(CommonObjectDetectorBase* base_, bo
return false;
}
}

View File

@@ -0,0 +1,479 @@
#include "common_det_intel_impl.h"
#include <cmath>
#include <fstream>
#include "sv_util.h"
#define SV_MODEL_DIR "/SpireCV/models/"
#define SV_ROOT_DIR "/SpireCV/"
namespace sv
{
#ifdef WITH_INTEL
using namespace cv;
using namespace std;
using namespace dnn;
#endif
float sigmoid_function(float a)
{
float b = 1. / (1. + exp(-a));
return b;
}
cv::Mat letterbox(cv::Mat &img_, std::vector<float> &paddings)
{
std::vector<int> new_shape = {640, 640};
// Get current image shape [height, width]
int img_h = img_.rows;
int img_w = img_.cols;
// Compute scale ratio(new / old) and target resized shape
float scale = std::min(new_shape[1] * 1.0 / img_h, new_shape[0] * 1.0 / img_w);
int resize_h = int(round(img_h * scale));
int resize_w = int(round(img_w * scale));
paddings[0] = scale;
// Compute padding
int pad_h = new_shape[1] - resize_h;
int pad_w = new_shape[0] - resize_w;
// Resize and pad image while meeting stride-multiple constraints
cv::Mat resized_img;
cv::resize(img_, resized_img, cv::Size(resize_w, resize_h));
// divide padding into 2 sides
float half_h = pad_h * 1.0 / 2;
float half_w = pad_w * 1.0 / 2;
paddings[1] = half_h;
paddings[2] = half_w;
// Compute padding boarder
int top = int(round(half_h - 0.1));
int bottom = int(round(half_h + 0.1));
int left = int(round(half_w - 0.1));
int right = int(round(half_w + 0.1));
// Add border
cv::copyMakeBorder(resized_img, resized_img, top, bottom, left, right, 0, cv::Scalar(114, 114, 114));
return resized_img;
}
CommonObjectDetectorIntelImpl::CommonObjectDetectorIntelImpl()
{
}
CommonObjectDetectorIntelImpl::~CommonObjectDetectorIntelImpl()
{
}
void CommonObjectDetectorIntelImpl::intelDetect(
CommonObjectDetectorBase *base_,
cv::Mat img_,
std::vector<float> &boxes_x_,
std::vector<float> &boxes_y_,
std::vector<float> &boxes_w_,
std::vector<float> &boxes_h_,
std::vector<int> &boxes_label_,
std::vector<float> &boxes_score_,
std::vector<cv::Mat> &boxes_seg_,
bool input_4k_)
{
#ifdef WITH_INTEL
int input_h = base_->getInputH();
int input_w = base_->getInputW();
bool with_segmentation = base_->withSegmentation();
double thrs_conf = base_->getThrsConf();
double thrs_nms = base_->getThrsNms();
if (with_segmentation)
{
std::vector<float> paddings(3); // scale, half_h, half_w
this->preprocess_img_seg(img_, paddings);
infer_request.start_async();
infer_request.wait();
// Postprocess
this->postprocess_img_seg(img_, paddings, boxes_x_, boxes_y_, boxes_w_, boxes_h_, boxes_label_, boxes_score_, boxes_seg_, thrs_conf, thrs_nms);
}
else
{
// Preprocess
this->preprocess_img(img_);
// Run inference
infer_request.start_async();
infer_request.wait();
// Postprocess
this->postprocess_img(boxes_x_, boxes_y_, boxes_w_, boxes_h_, boxes_label_, boxes_score_, thrs_conf, thrs_nms);
}
#endif
}
bool CommonObjectDetectorIntelImpl::intelSetup(CommonObjectDetectorBase *base_, bool input_4k_)
{
#ifdef WITH_INTEL
ov::Core core;
std::string dataset = base_->getDataset();
double thrs_conf = base_->getThrsConf();
double thrs_nms = base_->getThrsNms();
inpHeight = base_->getInputH();
inpWidth = base_->getInputW();
with_segmentation = base_->withSegmentation();
std::string model = base_->getModel();
std::string openvino_fn = get_home() + SV_MODEL_DIR + dataset + ".onnx";
std::vector<std::string> files;
_list_dir(get_home() + SV_MODEL_DIR, files, "-online.onnx", "Int-" + dataset + "-yolov5" + model + "_c");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
openvino_fn = get_home() + SV_MODEL_DIR + files[0];
}
if (inpWidth == 1280)
{
files.clear();
_list_dir(get_home() + SV_MODEL_DIR, files, "-online.onnx", "Int-" + dataset + "-yolov5" + model + "6_c");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
openvino_fn = get_home() + SV_MODEL_DIR + files[0];
}
else
{
openvino_fn = get_home() + SV_MODEL_DIR + dataset + "_HD.onnx";
}
}
if (with_segmentation)
{
base_->setInputH(640);
base_->setInputW(640);
files.clear();
_list_dir(get_home() + SV_MODEL_DIR, files, "-online.onnx", "Int-" + dataset + "-yolov5" + model + "_seg_c");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
openvino_fn = get_home() + SV_MODEL_DIR + files[0];
}
else
{
openvino_fn = get_home() + SV_MODEL_DIR + dataset + "_SEG.onnx";
}
}
std::cout << "Load: " << openvino_fn << std::endl;
if (!is_file_exist(openvino_fn))
{
throw std::runtime_error("SpireCV (104) Error loading the CommonObject OpenVINO model (File Not Exist)");
}
if (input_4k_ && with_segmentation)
{
throw std::runtime_error("SpireCV (106) Resolution 4K DO NOT Support Segmentation!");
}
if (with_segmentation)
{
this->compiled_model = core.compile_model(openvino_fn, "GPU");
this->infer_request = compiled_model.create_infer_request();
}
else
{
std::shared_ptr<ov::Model> model_ = core.read_model(openvino_fn);
ov::preprocess::PrePostProcessor Pre_P = ov::preprocess::PrePostProcessor(model_);
Pre_P.input().tensor().set_element_type(ov::element::u8).set_layout("NHWC").set_color_format(ov::preprocess::ColorFormat::RGB);
Pre_P.input().preprocess().convert_element_type(ov::element::f32).convert_color(ov::preprocess::ColorFormat::RGB).scale({255, 255, 255}); // .scale({ 112, 112, 112 });
Pre_P.input().model().set_layout("NCHW");
Pre_P.output().tensor().set_element_type(ov::element::f32);
model_ = Pre_P.build();
this->compiled_model = core.compile_model(model_, "GPU");
this->infer_request = compiled_model.create_infer_request();
}
return true;
#endif
return false;
}
void CommonObjectDetectorIntelImpl::preprocess_img(cv::Mat &img_)
{
#ifdef WITH_INTEL
float width = img_.cols;
float height = img_.rows;
cv::Size new_shape = cv::Size(inpHeight, inpWidth);
float r = float(new_shape.width / max(width, height));
int new_unpadW = int(round(width * r));
int new_unpadH = int(round(height * r));
cv::resize(img_, resize.resized_image, cv::Size(new_unpadW, new_unpadH), 0, 0, cv::INTER_AREA);
resize.resized_image = resize.resized_image;
resize.dw = new_shape.width - new_unpadW;
resize.dh = new_shape.height - new_unpadH;
cv::Scalar color = cv::Scalar(100, 100, 100);
cv::copyMakeBorder(resize.resized_image, resize.resized_image, 0, resize.dh, 0, resize.dw, cv::BORDER_CONSTANT, color);
this->rx = (float)img_.cols / (float)(resize.resized_image.cols - resize.dw);
this->ry = (float)img_.rows / (float)(resize.resized_image.rows - resize.dh);
if (with_segmentation)
{
cv::Mat blob = cv::dnn::blobFromImage(resize.resized_image, 1 / 255.0, cv::Size(640, 640), cv::Scalar(0, 0, 0), true);
auto input_port = compiled_model.input();
ov::Tensor input_tensor(input_port.get_element_type(), input_port.get_shape(), blob.ptr(0));
infer_request.set_input_tensor(input_tensor);
}
else
{
float *input_data = (float *)resize.resized_image.data;
input_tensor = ov::Tensor(compiled_model.input().get_element_type(), compiled_model.input().get_shape(), input_data);
infer_request.set_input_tensor(input_tensor);
}
#endif
}
void CommonObjectDetectorIntelImpl::preprocess_img_seg(cv::Mat &img_, std::vector<float> &paddings)
{
#ifdef WITH_INTEL
cv::Mat masked_img;
cv::Mat resized_img = letterbox(img_, paddings); // resize to (640,640) by letterbox
// BGR->RGB, u8(0-255)->f32(0.0-1.0), HWC->NCHW
cv::Mat blob = cv::dnn::blobFromImage(resized_img, 1 / 255.0, cv::Size(640, 640), cv::Scalar(0, 0, 0), true);
// Get input port for model with one input
auto input_port = compiled_model.input();
// Create tensor from external memory
ov::Tensor input_tensor(input_port.get_element_type(), input_port.get_shape(), blob.ptr(0));
// Set input tensor for model with one input
infer_request.set_input_tensor(input_tensor);
#endif
}
void CommonObjectDetectorIntelImpl::postprocess_img_seg(cv::Mat &img_,
std::vector<float> &paddings,
std::vector<float> &boxes_x_,
std::vector<float> &boxes_y_,
std::vector<float> &boxes_w_,
std::vector<float> &boxes_h_,
std::vector<int> &boxes_label_,
std::vector<float> &boxes_score_,
std::vector<cv::Mat> &boxes_seg_,
double &thrs_conf,
double &thrs_nms)
{
#ifdef WITH_INTEL
const ov::Tensor &detect = infer_request.get_output_tensor(0);
ov::Shape detect_shape = detect.get_shape();
const ov::Tensor &proto = infer_request.get_output_tensor(1);
ov::Shape proto_shape = proto.get_shape();
cv::Mat detect_buffer(detect_shape[1], detect_shape[2], CV_32F, detect.data());
cv::Mat proto_buffer(proto_shape[1], proto_shape[2] * proto_shape[3], CV_32F, proto.data());
cv::RNG rng;
float conf_threshold = thrs_conf;
float nms_threshold = thrs_nms;
std::vector<cv::Rect> boxes;
std::vector<int> class_ids;
std::vector<float> class_scores;
std::vector<float> confidences;
std::vector<cv::Mat> masks;
float scale = paddings[0];
for (int i = 0; i < detect_buffer.rows; i++)
{
float confidence = detect_buffer.at<float>(i, 4);
if (confidence < conf_threshold)
{
continue;
}
cv::Mat classes_scores = detect_buffer.row(i).colRange(5, 85);
cv::Point class_id;
double score;
cv::minMaxLoc(classes_scores, NULL, &score, NULL, &class_id);
// class score: 0~1
if (score > 0.25)
{
cv::Mat mask = detect_buffer.row(i).colRange(85, 117);
float cx = detect_buffer.at<float>(i, 0);
float cy = detect_buffer.at<float>(i, 1);
float w = detect_buffer.at<float>(i, 2);
float h = detect_buffer.at<float>(i, 3);
int left = static_cast<int>((cx - 0.5 * w - paddings[2]) / scale);
int top = static_cast<int>((cy - 0.5 * h - paddings[1]) / scale);
int width = static_cast<int>(w / scale);
int height = static_cast<int>(h / scale);
cv::Rect box;
box.x = left;
box.y = top;
box.width = width;
box.height = height;
boxes.push_back(box);
class_ids.push_back(class_id.x);
class_scores.push_back(score);
confidences.push_back(confidence);
masks.push_back(mask);
}
}
// NMS
std::vector<int> indices;
cv::dnn::NMSBoxes(boxes, confidences, thrs_conf, thrs_nms, indices);
// cv::Mat rgb_mask;
cv::Mat rgb_mask = cv::Mat::zeros(img_.size(), img_.type());
for (size_t i = 0; i < indices.size(); i++)
{
int index = indices[i];
int class_id = class_ids[index];
cv::Rect box = boxes[index];
int x1 = std::max(0, box.x);
int y1 = std::max(0, box.y);
int x2 = std::max(0, box.br().x);
int y2 = std::max(0, box.br().y);
cv::Mat m = masks[index] * proto_buffer;
for (int col = 0; col < m.cols; col++)
{
m.at<float>(0, col) = sigmoid_function(m.at<float>(0, col));
}
cv::Mat m1 = m.reshape(1, 160); // 1x25600 -> 160x160
int mx1 = std::max(0, int((x1 * scale + paddings[2]) * 0.25));
int mx2 = std::max(0, int((x2 * scale + paddings[2]) * 0.25));
int my1 = std::max(0, int((y1 * scale + paddings[1]) * 0.25));
int my2 = std::max(0, int((y2 * scale + paddings[1]) * 0.25));
cv::Mat mask_roi = m1(cv::Range(my1, my2), cv::Range(mx1, mx2));
cv::Mat rm, det_mask;
cv::resize(mask_roi, rm, cv::Size(x2 - x1, y2 - y1));
for (int r = 0; r < rm.rows; r++)
{
for (int c = 0; c < rm.cols; c++)
{
float pv = rm.at<float>(r, c);
if (pv > 0.5)
{
rm.at<float>(r, c) = 1.0;
}
else
{
rm.at<float>(r, c) = 0.0;
}
}
}
rm = rm * rng.uniform(0, 255);
rm.convertTo(det_mask, CV_8UC1);
if ((y1 + det_mask.rows) >= img_.rows)
{
y2 = img_.rows - 1;
}
if ((x1 + det_mask.cols) >= img_.cols)
{
x2 = img_.cols - 1;
}
cv::Mat mask = cv::Mat::zeros(cv::Size(img_.cols, img_.rows), CV_8UC1);
det_mask(cv::Range(0, y2 - y1), cv::Range(0, x2 - x1)).copyTo(mask(cv::Range(y1, y2), cv::Range(x1, x2)));
add(rgb_mask, cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255)), rgb_mask, mask);
boxes_x_.push_back(box.x);
boxes_y_.push_back(box.y);
boxes_w_.push_back(box.width);
boxes_h_.push_back(box.height);
boxes_label_.push_back((int)class_id);
boxes_score_.push_back(class_scores[index]);
cv::Mat mask_j = mask.clone();
boxes_seg_.push_back(mask_j);
}
#endif
}
void CommonObjectDetectorIntelImpl::postprocess_img(std::vector<float> &boxes_x_,
std::vector<float> &boxes_y_,
std::vector<float> &boxes_w_,
std::vector<float> &boxes_h_,
std::vector<int> &boxes_label_,
std::vector<float> &boxes_score_,
double &thrs_conf,
double &thrs_nms)
{
#ifdef WITH_INTEL
const ov::Tensor &output_tensor = infer_request.get_output_tensor();
ov::Shape output_shape = output_tensor.get_shape();
float *detections = output_tensor.data<float>();
std::vector<cv::Rect> boxes;
vector<int> class_ids;
vector<float> confidences;
for (int i = 0; i < output_shape[1]; i++)
{
float *detection = &detections[i * output_shape[2]];
float confidence = detection[4];
if (confidence >= thrs_conf)
{
float *classes_scores = &detection[5];
cv::Mat scores(1, output_shape[2] - 5, CV_32FC1, classes_scores);
cv::Point class_id;
double max_class_score;
cv::minMaxLoc(scores, 0, &max_class_score, 0, &class_id);
if (max_class_score > thrs_conf)
{
confidences.push_back(confidence);
class_ids.push_back(class_id.x);
float x = detection[0];
float y = detection[1];
float w = detection[2];
float h = detection[3];
float xmin = x - (w / 2);
float ymin = y - (h / 2);
boxes.push_back(cv::Rect(xmin, ymin, w, h));
}
}
}
std::vector<int> nms_result;
cv::dnn::NMSBoxes(boxes, confidences, thrs_conf, thrs_nms, nms_result);
std::vector<Detection> output;
for (int i = 0; i < nms_result.size(); i++)
{
Detection result;
int idx = nms_result[i];
result.class_id = class_ids[idx];
result.confidence = confidences[idx];
result.box = boxes[idx];
output.push_back(result);
}
for (int i = 0; i < output.size(); i++)
{
auto detection = output[i];
auto box = detection.box;
auto classId = detection.class_id;
auto confidence = detection.confidence;
float xmax = box.x + box.width;
float ymax = box.y + box.height;
boxes_x_.push_back(this->rx * box.x);
boxes_y_.push_back(this->ry * box.y);
boxes_w_.push_back(this->rx * box.width);
boxes_h_.push_back(this->ry * box.height);
boxes_label_.push_back((int)detection.class_id);
boxes_score_.push_back(detection.confidence);
}
#endif
}
}

View File

@@ -0,0 +1,89 @@
#ifndef __SV_COMMON_DET_INTEL__
#define __SV_COMMON_DET_INTEL__
#include "sv_core.h"
#include <string>
#include <iostream>
#include <opencv2/dnn.hpp>
#include <opencv2/imgproc.hpp>
#include <opencv2/highgui.hpp>
#include <string>
#include <chrono>
#ifdef WITH_INTEL
#include <openvino/openvino.hpp>
#endif
struct Resize
{
cv::Mat resized_image;
int dw;
int dh;
};
struct Detection
{
int class_id;
float confidence;
cv::Rect box;
};
namespace sv
{
class CommonObjectDetectorIntelImpl
{
public:
CommonObjectDetectorIntelImpl();
~CommonObjectDetectorIntelImpl();
bool intelSetup(CommonObjectDetectorBase *base_, bool input_4k_);
void intelDetect(
CommonObjectDetectorBase *base_,
cv::Mat img_,
std::vector<float> &boxes_x_,
std::vector<float> &boxes_y_,
std::vector<float> &boxes_w_,
std::vector<float> &boxes_h_,
std::vector<int> &boxes_label_,
std::vector<float> &boxes_score_,
std::vector<cv::Mat> &boxes_seg_,
bool input_4k_);
void preprocess_img(cv::Mat &img_);
void preprocess_img_seg(cv::Mat &img_, std::vector<float> &paddings);
void postprocess_img_seg(cv::Mat &img_,
std::vector<float> &paddings,
std::vector<float> &boxes_x_,
std::vector<float> &boxes_y_,
std::vector<float> &boxes_w_,
std::vector<float> &boxes_h_,
std::vector<int> &boxes_label_,
std::vector<float> &boxes_score_,
std::vector<cv::Mat> &boxes_seg_,
double &thrs_conf,
double &thrs_nms);
void postprocess_img(std::vector<float> &boxes_x_,
std::vector<float> &boxes_y_,
std::vector<float> &boxes_w_,
std::vector<float> &boxes_h_,
std::vector<int> &boxes_label_,
std::vector<float> &boxes_score_,
double &thrs_conf,
double &thrs_nms);
#ifdef WITH_INTEL
int inpWidth;
int inpHeight;
bool with_segmentation;
float rx; // the width ratio of original image and resized image
float ry; // the height ratio of original image and resized image
Resize resize;
ov::Tensor input_tensor;
ov::InferRequest infer_request;
ov::CompiledModel compiled_model;
#endif
};
}
#endif

View File

@@ -8,6 +8,10 @@
#include "common_det_cuda_impl.h"
#endif
#ifdef WITH_INTEL
#include <openvino/openvino.hpp>
#include "common_det_intel_impl.h"
#endif
namespace sv {
@@ -18,6 +22,10 @@ CommonObjectDetector::CommonObjectDetector(bool input_4k)
#ifdef WITH_CUDA
this->_cuda_impl = new CommonObjectDetectorCUDAImpl;
#endif
#ifdef WITH_INTEL
this->_intel_impl = new CommonObjectDetectorIntelImpl;
#endif
}
CommonObjectDetector::~CommonObjectDetector()
{
@@ -28,6 +36,10 @@ bool CommonObjectDetector::setupImpl()
#ifdef WITH_CUDA
return this->_cuda_impl->cudaSetup(this, this->_input_4k);
#endif
#ifdef WITH_INTEL
return this->_intel_impl->intelSetup(this, this->_input_4k);
#endif
return false;
}
@@ -53,14 +65,23 @@ void CommonObjectDetector::detectImpl(
boxes_label_,
boxes_score_,
boxes_seg_,
this->_input_4k
);
this->_input_4k);
#endif
#ifdef WITH_INTEL
this->_intel_impl->intelDetect(
this,
img_,
boxes_x_,
boxes_y_,
boxes_w_,
boxes_h_,
boxes_label_,
boxes_score_,
boxes_seg_,
this->_input_4k);
#endif
}
}

View File

@@ -1,6 +1,7 @@
#include "landing_det_cuda_impl.h"
#include <cmath>
#include <fstream>
#include "sv_util.h"
#define SV_MODEL_DIR "/SpireCV/models/"
#define SV_ROOT_DIR "/SpireCV/"
@@ -50,6 +51,16 @@ bool LandingMarkerDetectorCUDAImpl::cudaSetup()
{
#ifdef WITH_CUDA
std::string trt_model_fn = get_home() + SV_MODEL_DIR + "LandingMarker.engine";
std::vector<std::string> files;
_list_dir(get_home() + SV_MODEL_DIR, files, "-online.engine", "Nv-LandingMarker-resnet34");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
trt_model_fn = get_home() + SV_MODEL_DIR + files[0];
}
std::cout << "Load: " << trt_model_fn << std::endl;
if (!is_file_exist(trt_model_fn))
{
throw std::runtime_error("SpireCV (104) Error loading the LandingMarker TensorRT model (File Not Exist)");

View File

@@ -0,0 +1,104 @@
#include "landing_det_intel_impl.h"
#include <cmath>
#include <fstream>
#include "sv_util.h"
#define SV_MODEL_DIR "/SpireCV/models/"
#define SV_ROOT_DIR "/SpireCV/"
namespace sv
{
#ifdef WITH_INTEL
using namespace cv;
using namespace std;
using namespace dnn;
#endif
LandingMarkerDetectorIntelImpl::LandingMarkerDetectorIntelImpl()
{
}
LandingMarkerDetectorIntelImpl::~LandingMarkerDetectorIntelImpl()
{
}
bool LandingMarkerDetectorIntelImpl::intelSetup()
{
#ifdef WITH_INTEL
std::string onnx_model_fn = get_home() + SV_MODEL_DIR + "LandingMarker.onnx";
std::vector<std::string> files;
list_dir(get_home() + SV_MODEL_DIR, files, "-online.onnx", "Int-LandingMarker-resnet34");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
onnx_model_fn = get_home() + SV_MODEL_DIR + files[0];
}
if (!is_file_exist(onnx_model_fn))
{
throw std::runtime_error("SpireCV (104) Error loading the LandingMarker ONNX model (File Not Exist)");
}
// OpenVINO
ov::Core core;
std::shared_ptr<ov::Model> model = core.read_model(onnx_model_fn);
ov::preprocess::PrePostProcessor ppp = ov::preprocess::PrePostProcessor(model);
ppp.input().tensor().set_element_type(ov::element::u8).set_layout("NHWC").set_color_format(ov::preprocess::ColorFormat::RGB);
ppp.input().preprocess().convert_element_type(ov::element::f32).convert_color(ov::preprocess::ColorFormat::RGB).scale({255, 255, 255}); // .scale({ 112, 112, 112 });
ppp.input().model().set_layout("NCHW");
ppp.output().tensor().set_element_type(ov::element::f32);
model = ppp.build();
this->compiled_model = core.compile_model(model, "GPU");
this->infer_request = compiled_model.create_infer_request();
return true;
#endif
return false;
}
void LandingMarkerDetectorIntelImpl::intelRoiCNN(
std::vector<cv::Mat> &input_rois_,
std::vector<int> &output_labels_)
{
#ifdef WITH_INTEL
output_labels_.clear();
for (int i = 0; i < input_rois_.size(); i++)
{
cv::Mat e_roi = input_rois_[i];
// Get input port for model with one input
auto input_port = compiled_model.input();
// Create tensor from external memory
ov::Tensor input_tensor(input_port.get_element_type(), input_port.get_shape(), e_roi.ptr(0));
// Set input tensor for model with one input
infer_request.set_input_tensor(input_tensor);
//preprocess_img(e_roi);
// infer_request.infer();
infer_request.start_async();
infer_request.wait();
const ov::Tensor &output_tensor = infer_request.get_output_tensor();
ov::Shape output_shape = output_tensor.get_shape();
this->_p_prob = output_tensor.data<float>();
// Find max index
double max = 0;
int label = 0;
for (int i = 0; i < 11; ++i)
{
if (max < this->_p_prob[i])
{
max = this->_p_prob[i];
label = i;
}
}
output_labels_.push_back(label);
}
#endif
}
}

View File

@@ -0,0 +1,37 @@
#ifndef __SV_LANDING_DET_INTEL__
#define __SV_LANDING_DET_INTEL__
#include "sv_core.h"
#include <opencv2/opencv.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/tracking.hpp>
#include <string>
#include <chrono>
#ifdef WITH_INTEL
#include <openvino/openvino.hpp>
#endif
namespace sv
{
class LandingMarkerDetectorIntelImpl
{
public:
LandingMarkerDetectorIntelImpl();
~LandingMarkerDetectorIntelImpl();
bool intelSetup();
void intelRoiCNN(
std::vector<cv::Mat> &input_rois_,
std::vector<int> &output_labels_);
#ifdef WITH_INTEL
float *_p_prob;
ov::Tensor input_tensor;
ov::InferRequest infer_request;
ov::CompiledModel compiled_model;
#endif
};
}
#endif

View File

@@ -7,6 +7,10 @@
#include "landing_det_cuda_impl.h"
#endif
#ifdef WITH_INTEL
#include <openvino/openvino.hpp>
#include "landing_det_intel_impl.h"
#endif
namespace sv {
@@ -16,6 +20,10 @@ LandingMarkerDetector::LandingMarkerDetector()
#ifdef WITH_CUDA
this->_cuda_impl = new LandingMarkerDetectorCUDAImpl;
#endif
#ifdef WITH_INTEL
this->_intel_impl = new LandingMarkerDetectorIntelImpl;
#endif
}
LandingMarkerDetector::~LandingMarkerDetector()
{
@@ -26,6 +34,10 @@ bool LandingMarkerDetector::setupImpl()
#ifdef WITH_CUDA
return this->_cuda_impl->cudaSetup();
#endif
#ifdef WITH_INTEL
return this->_intel_impl->intelSetup();
#endif
return false;
}
@@ -40,11 +52,13 @@ void LandingMarkerDetector::roiCNN(
output_labels_
);
#endif
}
#ifdef WITH_INTEL
this->_intel_impl->intelRoiCNN(
input_rois_,
output_labels_
);
#endif
}
}

View File

@@ -1,6 +1,7 @@
#include "sot_ocv470_impl.h"
#include <cmath>
#include <fstream>
#include "sv_util.h"
#define SV_MODEL_DIR "/SpireCV/models/"
#define SV_ROOT_DIR "/SpireCV/"
@@ -30,9 +31,39 @@ bool SingleObjectTrackerOCV470Impl::ocv470Setup(SingleObjectTrackerBase* base_)
std::string net = get_home() + SV_MODEL_DIR + "dasiamrpn_model.onnx";
std::string kernel_cls1 = get_home() + SV_MODEL_DIR + "dasiamrpn_kernel_cls1.onnx";
std::string kernel_r1 = get_home() + SV_MODEL_DIR + "dasiamrpn_kernel_r1.onnx";
std::vector<std::string> files1, files2, files3;
_list_dir(get_home() + SV_MODEL_DIR, files1, ".onnx", "Ocv-DaSiamRPN-Model-");
_list_dir(get_home() + SV_MODEL_DIR, files2, ".onnx", "Ocv-DaSiamRPN-Kernel-CLS1-");
_list_dir(get_home() + SV_MODEL_DIR, files3, ".onnx", "Ocv-DaSiamRPN-Kernel-R1-");
if (files1.size() > 0 && files2.size() > 0 && files3.size() > 0)
{
std::sort(files1.rbegin(), files1.rend(), _comp_str_lesser);
std::sort(files2.rbegin(), files2.rend(), _comp_str_lesser);
std::sort(files3.rbegin(), files3.rend(), _comp_str_lesser);
net = get_home() + SV_MODEL_DIR + files1[0];
kernel_cls1 = get_home() + SV_MODEL_DIR + files2[0];
kernel_r1 = get_home() + SV_MODEL_DIR + files3[0];
}
std::cout << "Load: " << net << std::endl;
std::cout << "Load: " << kernel_cls1 << std::endl;
std::cout << "Load: " << kernel_r1 << std::endl;
std::string backbone = get_home() + SV_MODEL_DIR + "nanotrack_backbone_sim.onnx";
std::string neckhead = get_home() + SV_MODEL_DIR + "nanotrack_head_sim.onnx";
std::vector<std::string> files4, files5;
_list_dir(get_home() + SV_MODEL_DIR, files4, ".onnx", "Ocv-NanoTrack-Backbone-SIM-");
_list_dir(get_home() + SV_MODEL_DIR, files5, ".onnx", "Ocv-NanoTrack-Head-SIM-");
if (files4.size() > 0 && files5.size() > 0)
{
std::sort(files4.rbegin(), files4.rend(), _comp_str_lesser);
std::sort(files5.rbegin(), files5.rend(), _comp_str_lesser);
backbone = get_home() + SV_MODEL_DIR + files4[0];
neckhead = get_home() + SV_MODEL_DIR + files5[0];
}
std::cout << "Load: " << backbone << std::endl;
std::cout << "Load: " << neckhead << std::endl;
try
{

View File

@@ -32,7 +32,7 @@ CameraAlgorithm::CameraAlgorithm()
// this->_allocator = NULL;
this->_t0 = std::chrono::system_clock::now();
this->alg_params_fn = _get_home() + SV_ROOT_DIR + "sv_algorithm_params.json";
this->alg_params_fn = _get_home() + SV_ROOT_DIR + "confs/sv_algorithm_params.json";
// std::cout << "CameraAlgorithm->alg_params_fn: " << this->alg_params_fn << std::endl;
// if (_is_file_exist(params_fn))
// this->loadAlgorithmParams(params_fn);
@@ -916,6 +916,14 @@ void CommonObjectDetectorBase::setInputW(int w_)
{
this->_input_w = w_;
}
std::string CommonObjectDetectorBase::getModel()
{
return this->_model;
}
int CommonObjectDetectorBase::getBatchSize()
{
return this->_batch_size;
}
void CommonObjectDetectorBase::warmUp()
{
@@ -1002,6 +1010,11 @@ void CommonObjectDetectorBase::detect(cv::Mat img_, TargetsInFrame& tgts_, Box*
if (this->_with_segmentation)
{
cv::Mat mask_j = boxes_seg[j].clone();
#ifdef WITH_INTEL
tgt.setMask(mask_j);
#endif
#ifdef WITH_CUDA
int maskh = mask_j.rows, maskw = mask_j.cols;
assert(maskh == maskw);
@@ -1031,6 +1044,7 @@ void CommonObjectDetectorBase::detect(cv::Mat img_, TargetsInFrame& tgts_, Box*
{
tgt.setMask(mask_j);
}
#endif
}
tgts_.targets.push_back(tgt);
@@ -1076,6 +1090,8 @@ void CommonObjectDetectorBase::_load()
this->_thrs_nms = 0.6;
this->_thrs_conf = 0.4;
this->_use_width_or_height = 0;
this->_batch_size = 1;
this->_model = "s";
for (auto i : detector_params_value) {
@@ -1083,6 +1099,12 @@ void CommonObjectDetectorBase::_load()
this->_dataset = i->value.toString();
std::cout << "dataset: " << this->_dataset << std::endl;
}
else if ("batchSize" == std::string(i->key)) {
this->_batch_size = i->value.toNumber();
}
else if ("model" == std::string(i->key)) {
this->_model = i->value.toString();
}
else if ("inputSize" == std::string(i->key)) {
// std::cout << "inputSize (old, new): " << this->_input_w << ", " << i->value.toNumber() << std::endl;
this->_input_w = i->value.toNumber();

View File

@@ -1,6 +1,7 @@
#include "veri_det_cuda_impl.h"
#include <cmath>
#include <fstream>
#include "sv_util.h"
#define SV_MODEL_DIR "/SpireCV/models/"
#define SV_ROOT_DIR "/SpireCV/"
@@ -75,6 +76,16 @@ namespace sv
{
#ifdef WITH_CUDA
std::string trt_model_fn = get_home() + SV_MODEL_DIR + "veri.engine";
std::vector<std::string> files;
_list_dir(get_home() + SV_MODEL_DIR, files, "-online.engine", "Nv-VERI-mobilenet_v3");
if (files.size() > 0)
{
std::sort(files.rbegin(), files.rend(), _comp_str_lesser);
trt_model_fn = get_home() + SV_MODEL_DIR + files[0];
}
std::cout << "Load: " << trt_model_fn << std::endl;
if (!is_file_exist(trt_model_fn))
{
throw std::runtime_error("SpireCV (104) Error loading the VeriDetector TensorRT model (File Not Exist)");

View File

@@ -0,0 +1,112 @@
#include "veri_det_intel_impl.h"
#include <cmath>
#include <fstream>
#define SV_MODEL_DIR "/SpireCV/models/"
#define SV_ROOT_DIR "/SpireCV/"
#include <iostream>
#include <cmath>
int BAT = 1;
float cosineSimilarity(float *vec1, float *vec2, int size)
{
// 计算向量的点积
float dotProduct = 0.0f;
for (int i = 0; i < size; ++i)
{
dotProduct += vec1[i] * vec2[i];
}
// 计算向量的模长
float magnitudeVec1 = 0.0f;
float magnitudeVec2 = 0.0f;
for (int i = 0; i < size; ++i)
{
magnitudeVec1 += vec1[i] * vec1[i];
magnitudeVec2 += vec2[i] * vec2[i];
}
magnitudeVec1 = std::sqrt(magnitudeVec1);
magnitudeVec2 = std::sqrt(magnitudeVec2);
// 计算余弦相似性
float similarity = dotProduct / (magnitudeVec1 * magnitudeVec2);
return similarity;
}
namespace sv
{
#ifdef WITH_INTEL
using namespace cv;
using namespace std;
using namespace dnn;
#endif
VeriDetectorIntelImpl::VeriDetectorIntelImpl()
{
}
VeriDetectorIntelImpl::~VeriDetectorIntelImpl()
{
}
bool VeriDetectorIntelImpl::intelSetup()
{
#ifdef WITH_INTEL
std::string onnx_model_fn = get_home() + SV_MODEL_DIR + "veri.onnx";
if (!is_file_exist(onnx_model_fn))
{
throw std::runtime_error("SpireCV (104) Error loading the VeriDetector openVINO model (File Not Exist)");
}
// OpenVINO
ov::Core core;
this->compiled_model = core.compile_model(onnx_model_fn, "GPU");
this->infer_request = compiled_model.create_infer_request();
return true;
#endif
return false;
}
void VeriDetectorIntelImpl::intelRoiCNN(
std::vector<cv::Mat> &input_rois_,
std::vector<float> &output_labels_)
{
#ifdef WITH_INTEL
Mat blobs;
blobFromImages(input_rois_, blobs, 1 / 255.0, Size(224, 224), Scalar(0, 0, 0), true, true);
auto input_port = compiled_model.input();
ov::Tensor input_tensor(input_port.get_element_type(), input_port.get_shape(), blobs.ptr(0));
infer_request.infer();
const ov::Tensor &label_pre = infer_request.get_output_tensor(0);
this->_p_prob1 = label_pre.data<float>();
const ov::Tensor &proto_pre = infer_request.get_output_tensor(1);
this->_p_prob2 = proto_pre.data<float>();
// Find max index
double max = 0;
int label = 0;
for (int i = 0; i < 576; ++i)
{
if (max < this->_p_prob1[i])
{
max = this->_p_prob1[i];
label = i;
}
}
float similarity = cosineSimilarity(this->_p_prob2, this->_p_prob2 + 1280, 1280);
output_labels_.push_back(label);
output_labels_.push_back(similarity);
#endif
}
}

View File

@@ -0,0 +1,41 @@
#ifndef __SV_VERI_DET_INTEL__
#define __SV_VERI_DET_INTEL__
#include "sv_core.h"
#include <opencv2/opencv.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/tracking.hpp>
#include <string>
#include <chrono>
#ifdef WITH_INTEL
#include <openvino/openvino.hpp>
#endif
namespace sv
{
class VeriDetectorIntelImpl
{
public:
VeriDetectorIntelImpl();
~VeriDetectorIntelImpl();
bool intelSetup();
void intelRoiCNN(
std::vector<cv::Mat> &input_rois_,
std::vector<float> &output_labels_);
#ifdef WITH_INTEL
float *_p_data;
float *_p_prob1;
float *_p_prob2;
ov::Tensor input_tensor;
ov::InferRequest infer_request;
ov::CompiledModel compiled_model;
#endif
};
}
#endif

View File

@@ -10,6 +10,11 @@
#include "veri_det_cuda_impl.h"
#endif
#ifdef WITH_INTEL
#include <openvino/openvino.hpp>
#include "veri_det_intel_impl.h"
#endif
#define SV_ROOT_DIR "/SpireCV/"
namespace sv
@@ -20,6 +25,10 @@ namespace sv
#ifdef WITH_CUDA
this->_cuda_impl = new VeriDetectorCUDAImpl;
#endif
#ifdef WITH_INTEL
this->_intel_impl = new VeriDetectorIntelImpl;
#endif
}
VeriDetector::~VeriDetector()
{
@@ -50,6 +59,9 @@ namespace sv
return this->_cuda_impl->cudaSetup();
#endif
#ifdef WITH_INTEL
return this->_intel_impl->intelSetup();
#endif
return false;
}
@@ -63,6 +75,12 @@ namespace sv
input_rois_,
output_labels_);
#endif
#ifdef WITH_INTEL
this->_intel_impl->intelRoiCNN(
input_rois_,
output_labels_);
#endif
}
void VeriDetector::detect(cv::Mat img_, const cv::Rect &bounding_box_, sv::Target &tgt)
@@ -94,26 +112,23 @@ namespace sv
cv::Mat img_ground = cv::imread(img_ground_dir);
cv::resize(img_ground, img_ground, cv::Size(224, 224));
std::vector<cv::Mat> input_rois_ = {crop, img_ground};
#ifdef WITH_CUDA
std::vector<float> output_labels;
#ifdef WITH_CUDA
roiCNN(input_rois_, output_labels);
#endif
// auto t1 = std::chrono::system_clock::now();
// tgts_.setFPS(1000.0 / std::chrono::duration_cast<std::chrono::milliseconds>(t1 - this->_t0).count());
// this->_t0 = std::chrono::system_clock::now();
// tgts_.setTimeNow();
#ifdef WITH_INTEL
roiCNN(input_rois_, output_labels);
#endif
if (output_labels.size() > 0)
{
// tgt.category_id = output_labels[0];
tgt.sim_score = output_labels[1];
// tgts_.targets.push_back(tgt);
}
#endif
}
void VeriDetector::getSubwindow(cv::Mat &dstCrop, cv::Mat &srcImg, int originalSz, int resizeSz)
void VeriDetector::getSubwindow(cv::Mat &dstCrop, cv::Mat &srcImg, int originalSz, int resizeSz)
{
cv::Scalar avgChans = mean(srcImg);
cv::Size imgSz = srcImg.size();

View File

@@ -28,6 +28,7 @@ GX40GimbalDriver::GX40GimbalDriver(amovGimbal::IOStreamBase *_IO) : amovGimbal::
targetPos[2] = 0;
parserState = GX40::GIMBAL_FRAME_PARSER_STATE_IDLE;
upDataTs = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()) - std::chrono::milliseconds(2000);
}
/**
@@ -107,7 +108,8 @@ uint32_t GX40GimbalDriver::pack(IN uint32_t cmd, uint8_t *pPayload, uint8_t payl
// 惯导数据填充
std::chrono::milliseconds nowTs = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch());
// over 1s GNSS has losed
if ((nowTs.count() - upDataTs.count()) < std::chrono::milliseconds(1500).count())
if ((nowTs.count() - upDataTs.count()) < std::chrono::milliseconds(1500).count() &&
cmd == GX40::GIMBAL_CMD_NOP)
{
primary->selfRoll = (int16_t)(-(carrierPos.roll / 0.01f));
primary->selfPitch = (int16_t)(-(carrierPos.pitch / 0.01f));

View File

@@ -140,6 +140,8 @@ public:
double getThrsConf();
int useWidthOrHeight();
bool withSegmentation();
std::string getModel();
int getBatchSize();
protected:
virtual bool setupImpl();
virtual void detectImpl(
@@ -166,6 +168,8 @@ protected:
double _thrs_conf;
int _use_width_or_height;
bool _with_segmentation;
std::string _model;
int _batch_size;
};

View File

@@ -25,7 +25,6 @@ public:
double line_location_a2;
bool is_load_parameter;
std::string line_color;
protected:
@@ -40,4 +39,4 @@ protected:
void seg(cv::Mat line_area_, cv::Mat line_area_a1_, cv::Mat line_area_a2_, std::string line_color_, cv::Point &center_, int &area_, cv::Point &center_a1_, cv::Point &center_a2_);
};
}
#endif
#endif

View File

@@ -8,33 +8,36 @@
#include <string>
#include <chrono>
namespace sv {
namespace sv
{
class CommonObjectDetectorCUDAImpl;
class CommonObjectDetectorIntelImpl;
class CommonObjectDetector : public CommonObjectDetectorBase
{
public:
CommonObjectDetector(bool input_4k=false);
CommonObjectDetector(bool input_4k = false);
~CommonObjectDetector();
protected:
bool setupImpl();
void detectImpl(
cv::Mat img_,
std::vector<float>& boxes_x_,
std::vector<float>& boxes_y_,
std::vector<float>& boxes_w_,
std::vector<float>& boxes_h_,
std::vector<int>& boxes_label_,
std::vector<float>& boxes_score_,
std::vector<cv::Mat>& boxes_seg_
);
std::vector<float> &boxes_x_,
std::vector<float> &boxes_y_,
std::vector<float> &boxes_w_,
std::vector<float> &boxes_h_,
std::vector<int> &boxes_label_,
std::vector<float> &boxes_score_,
std::vector<cv::Mat> &boxes_seg_);
CommonObjectDetectorCUDAImpl *_cuda_impl;
CommonObjectDetectorIntelImpl *_intel_impl;
CommonObjectDetectorCUDAImpl* _cuda_impl;
bool _input_4k;
};
}
#endif

View File

@@ -12,6 +12,7 @@
namespace sv {
class LandingMarkerDetectorCUDAImpl;
class LandingMarkerDetectorIntelImpl;
class LandingMarkerDetector : public LandingMarkerDetectorBase
{
@@ -25,7 +26,8 @@ protected:
std::vector<int>& output_labels_
);
LandingMarkerDetectorCUDAImpl* _cuda_impl;
LandingMarkerDetectorCUDAImpl *_cuda_impl;
LandingMarkerDetectorIntelImpl *_intel_impl;
};

View File

@@ -8,8 +8,8 @@
#include <opencv2/tracking.hpp>
#include <string>
#include <chrono>
#include <Eigen/Dense>
//#include <Eigen/Dense>
#include <eigen3/Eigen/Dense>
namespace sv {

View File

@@ -11,33 +11,34 @@
namespace sv
{
class VeriDetectorCUDAImpl;
class VeriDetectorCUDAImpl;
class VeriDetectorIntelImpl;
class VeriDetector : public LandingMarkerDetectorBase
{
public:
VeriDetector();
~VeriDetector();
class VeriDetector : public LandingMarkerDetectorBase
{
public:
VeriDetector();
~VeriDetector();
void detect(cv::Mat img_, const cv::Rect &bounding_box_, sv::Target &tgt);
void detect(cv::Mat img_, const cv::Rect &bounding_box_, sv::Target &tgt);
protected:
void _load();
bool setupImpl();
void roiCNN(
std::vector<cv::Mat> &input_rois_,
std::vector<float> &output_labels_);
void getSubwindow(cv::Mat &dstCrop, cv::Mat &srcImg, int originalSz, int resizeSz);
protected:
void _load();
bool setupImpl();
void roiCNN(
std::vector<cv::Mat> &input_rois_,
std::vector<float> &output_labels_);
void getSubwindow(cv::Mat &dstCrop, cv::Mat &srcImg, int originalSz, int resizeSz);
std::string vehicle_id;
std::string vehicle_id;
// Save the target bounding box for each frame.
std::vector<float> targetSz = {0, 0}; // H and W of bounding box
std::vector<float> targetPos = {0, 0}; // center point of bounding box (x, y)
// Save the target bounding box for each frame.
std::vector<float> targetSz = {0, 0}; // H and W of bounding box
std::vector<float> targetPos = {0, 0}; // center point of bounding box (x, y)
VeriDetectorCUDAImpl *_cuda_impl;
};
VeriDetectorCUDAImpl *_cuda_impl;
VeriDetectorIntelImpl *_intel_impl;
};
}
#endif

View File

@@ -333,7 +333,7 @@ class CameraBase {
public:
CameraBase(CameraType type=CameraType::NONE, int id=0);
~CameraBase();
void open(CameraType type=CameraType::WEBCAM, int id=0);
void open(CameraType type=CameraType::V4L2CAM, int id=0);
bool read(cv::Mat& image);
void release();
@@ -347,7 +347,9 @@ public:
double getSaturation();
double getHue();
double getExposure();
std::string getFourcc();
bool isRunning();
void setFourcc(std::string fourcc);
void setWH(int width, int height);
void setFps(int fps);
void setIp(std::string ip);
@@ -383,6 +385,7 @@ protected:
double _saturation;
double _hue;
double _exposure;
std::string _fourcc;
};

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 640,
"withSegmentation": true,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": true,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 1280,
"withSegmentation": false,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": false,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 640,
"withSegmentation": true,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": true,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 640,
"withSegmentation": false,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": false,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 1280,
"withSegmentation": false,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": false,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 640,
"withSegmentation": false,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": true,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 640,
"withSegmentation": true,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": true,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 640,
"withSegmentation": true,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": true,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 640,
"withSegmentation": true,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": true,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -1,11 +1,13 @@
{
"CommonObjectDetector": {
"dataset": "COCO",
"model": "s",
"batchSize": 1,
"inputSize": 640,
"withSegmentation": true,
"nmsThrs": 0.6,
"scoreThrs": 0.4,
"useWidthOrHeight": 1,
"withSegmentation": true,
"datasetPersonVehicle": {
"person": [0.5, 1.8],
"car": [4.1, 1.5],

View File

@@ -9,13 +9,14 @@ int main(int argc, char *argv[]) {
// 实例化Aruco检测器类
sv::ArucoDetector ad;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
ad.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
ad.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
ad.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(ad.image_width, ad.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@@ -8,9 +8,9 @@ using namespace std;
int main(int argc, char *argv[]) {
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(1280, 720);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
while (1)

View File

@@ -11,13 +11,14 @@ int main(int argc, char *argv[])
// 实例化 color line detection 检测器类
sv::ColorLineDetector cld;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
cld.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
cld.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
cld.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(cld.image_width, cld.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@@ -9,13 +9,14 @@ int main(int argc, char *argv[]) {
// 实例化 通用目标 检测器类
sv::CommonObjectDetector cod;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
cod.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
cod.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(cod.image_width, cod.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@@ -40,18 +40,20 @@ int main(int argc, char *argv[]) {
// 实例化 框选目标跟踪类
sv::SingleObjectTracker sot;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
sot.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
sot.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
sv::CommonObjectDetector cod;
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
cod.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
cod.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(cod.image_width, cod.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;

View File

@@ -9,13 +9,14 @@ int main(int argc, char *argv[]) {
// 实例化 椭圆 检测器类
sv::EllipseDetector ed;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
ed.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
ed.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
ed.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(ed.image_width, ed.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@@ -58,10 +58,12 @@ int main(int argc, char *argv[])
// 实例化 框选目标跟踪类
sv::SingleObjectTracker sot;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
sot.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
sot.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
sv::CommonObjectDetector cod;
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
cod.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
cod.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
@@ -256,4 +258,4 @@ void GimableCallback(double &frame_ang_r, double &frame_ang_p, double &frame_ang
count = 0;
}
count++;
}
}

View File

@@ -58,7 +58,8 @@ int main(int argc, char *argv[])
// 实例化 圆形降落标志 检测器类
sv::LandingMarkerDetector lmd;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
lmd.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
lmd.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
lmd.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
@@ -144,4 +145,4 @@ void GimableCallback(double &frame_ang_r, double &frame_ang_p, double &frame_ang
count = 0;
}
count++;
}
}

View File

@@ -67,7 +67,8 @@ int main(int argc, char *argv[])
// 实例化Aruco检测器类
sv::ArucoDetector ad;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
ad.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
ad.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
ad.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
sv::UDPServer udp;
// 实例化OpenCV的Mat类用于内存单帧图像

View File

@@ -9,13 +9,14 @@ int main(int argc, char *argv[]) {
// 实例化 圆形降落标志 检测器类
sv::LandingMarkerDetector lmd;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
lmd.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
lmd.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
lmd.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(lmd.image_width, lmd.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@@ -9,17 +9,19 @@ int main(int argc, char *argv[]) {
// 实例化
sv::CommonObjectDetector cod;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
cod.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
cod.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
sv::MultipleObjectTracker mot;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
mot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
mot.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
mot.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
mot.init(&cod);
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(mot.image_width, mot.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@@ -28,15 +28,15 @@ int main(int argc, char *argv[]) {
// 实例化 框选目标跟踪类
sv::SingleObjectTracker sot;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
// sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml");
// sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1920x1080.yaml");
sot.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
sot.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(sot.image_width, sot.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// cv::VideoCapture cap("/home/amov/SpireCV/test/tracking_1280x720.mp4");
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;

View File

@@ -5,7 +5,7 @@
#include <stdio.h>
#define SERV_PORT 20166
typedef unsigned char byte;
using namespace std;
@@ -23,9 +23,9 @@ int main(int argc, char *argv[]) {
int upd_msg_len = 1024 * 6; // max_objects = 100
byte upd_msg[upd_msg_len];
unsigned char upd_msg[upd_msg_len];
int msg_queue_len = 1024 * 1024; // 1M
byte msg_queue[msg_queue_len];
unsigned char msg_queue[msg_queue_len];
int addr_len = sizeof(struct sockaddr_in);
int start_index = 0, end_index = 0;
@@ -63,21 +63,21 @@ cout << n << ", " << start_index << ", " << end_index << endl;
if (end_index - i >= ilen + 2 && msg_queue[i+ilen] == 0xFB && msg_queue[i+ilen+1] == 0xFD)
{
cout << "FOUND 0xFAFC & 0xFBFD" << endl;
byte* msg_type = reinterpret_cast<byte*>(&msg_queue[i+2]);
unsigned char* msg_type = reinterpret_cast<unsigned char*>(&msg_queue[i+2]);
cout << "Type: " << (int) *msg_type << endl;
unsigned short* year = reinterpret_cast<unsigned short*>(&msg_queue[i+7]);
byte* month = reinterpret_cast<byte*>(&msg_queue[i+9]);
byte* day = reinterpret_cast<byte*>(&msg_queue[i+10]);
byte* hour = reinterpret_cast<byte*>(&msg_queue[i+11]);
byte* minute = reinterpret_cast<byte*>(&msg_queue[i+12]);
byte* second = reinterpret_cast<byte*>(&msg_queue[i+13]);
unsigned char* month = reinterpret_cast<unsigned char*>(&msg_queue[i+9]);
unsigned char* day = reinterpret_cast<unsigned char*>(&msg_queue[i+10]);
unsigned char* hour = reinterpret_cast<unsigned char*>(&msg_queue[i+11]);
unsigned char* minute = reinterpret_cast<unsigned char*>(&msg_queue[i+12]);
unsigned char* second = reinterpret_cast<unsigned char*>(&msg_queue[i+13]);
unsigned short* millisecond = reinterpret_cast<unsigned short*>(&msg_queue[i+14]);
cout << "Time: " << *year << "-" << (int) *month << "-" << (int) *day << " " << (int) *hour << ":" << (int) *minute << ":" << (int) *second << " " << *millisecond << endl;
byte* index_d1 = reinterpret_cast<byte*>(&msg_queue[i+16]);
byte* index_d2 = reinterpret_cast<byte*>(&msg_queue[i+17]);
byte* index_d3 = reinterpret_cast<byte*>(&msg_queue[i+18]);
byte* index_d4 = reinterpret_cast<byte*>(&msg_queue[i+19]);
unsigned char* index_d1 = reinterpret_cast<unsigned char*>(&msg_queue[i+16]);
unsigned char* index_d2 = reinterpret_cast<unsigned char*>(&msg_queue[i+17]);
unsigned char* index_d3 = reinterpret_cast<unsigned char*>(&msg_queue[i+18]);
unsigned char* index_d4 = reinterpret_cast<unsigned char*>(&msg_queue[i+19]);
int mp = i+20;
if ((*index_d4) & 0x01 == 0x01)
{
@@ -152,13 +152,13 @@ cout << n << ", " << start_index << ", " << end_index << endl;
}
for (int j=0; j<n_objects; j++)
{
byte* index_f1 = reinterpret_cast<byte*>(&msg_queue[mp]);
unsigned char* index_f1 = reinterpret_cast<unsigned char*>(&msg_queue[mp]);
mp++;
byte* index_f2 = reinterpret_cast<byte*>(&msg_queue[mp]);
unsigned char* index_f2 = reinterpret_cast<unsigned char*>(&msg_queue[mp]);
mp++;
byte* index_f3 = reinterpret_cast<byte*>(&msg_queue[mp]);
unsigned char* index_f3 = reinterpret_cast<unsigned char*>(&msg_queue[mp]);
mp++;
byte* index_f4 = reinterpret_cast<byte*>(&msg_queue[mp]);
unsigned char* index_f4 = reinterpret_cast<unsigned char*>(&msg_queue[mp]);
mp++;
if ((*index_f4) & 0x01 == 0x01 && (*index_f4) & 0x02 == 0x02)
{

View File

@@ -9,13 +9,13 @@ int main(int argc, char *argv[]) {
// 实例化Aruco检测器类
sv::ArucoDetector ad;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
ad.loadCameraParams("/home/amov/SpireCV/calib_webcam_640x480.yaml");
ad.loadCameraParams("/home/amov/SpireCV/calib_webcam_1280x720.yaml");
// 打开摄像头
sv::Camera cap;
cap.setWH(640, 480);
cap.setWH(ad.image_width, ad.image_height);
cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
sv::UDPServer udp;
// 实例化OpenCV的Mat类用于内存单帧图像

View File

@@ -20,16 +20,18 @@ int main(int argc, char *argv[])
// 实例化 框选目标跟踪类
sv::VeriDetector veri;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
veri.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
veri.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
veri.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
sv::CommonObjectDetector cod;
cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml");
cod.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
cod.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(cod.image_width, cod.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;

View File

@@ -9,13 +9,14 @@ int main(int argc, char *argv[]) {
// 实例化 通用目标 检测器类
sv::CommonObjectDetector cod;
// 手动导入相机参数如果使用Amov的G1等吊舱或相机则可以忽略该步骤将自动下载相机参数文件
cod.loadCameraParams("/home/amov/SpireCV/calib_webcam_640x480.yaml");
cod.loadCameraParams(sv::get_home() + "/SpireCV/confs/calib_webcam_1280x720.yaml");
cod.loadAlgorithmParams(sv::get_home() + "/SpireCV/confs/sv_algorithm_params.json");
// 打开摄像头
sv::Camera cap;
// cap.setWH(640, 480);
// cap.setFps(30);
cap.open(sv::CameraType::WEBCAM, 0); // CameraID 0
cap.setWH(cod.image_width, cod.image_height);
cap.setFps(30);
cap.open(sv::CameraType::V4L2CAM, 0); // CameraID 0
// 实例化OpenCV的Mat类用于内存单帧图像
cv::Mat img;
int frame_id = 0;
@@ -23,7 +24,7 @@ int main(int argc, char *argv[]) {
// 实例化视频保存类
sv::VideoWriter vw;
// 设置保存路径"/home/amov/Videos"保存图像尺寸640480帧频25Hz同步保存检测结果.svj
vw.setup("/home/amov/Videos", cv::Size(640, 480), 25, true);
vw.setup(sv::get_home() + "/Videos", cv::Size(cod.image_width, cod.image_height), 25, true);
while (1)
{
@@ -31,7 +32,7 @@ int main(int argc, char *argv[]) {
sv::TargetsInFrame tgts(frame_id++);
// 读取一帧图像到img
cap.read(img);
cv::resize(img, img, cv::Size(640, 480));
cv::resize(img, img, cv::Size(cod.image_width, cod.image_height));
// 执行通用目标检测
cod.detect(img, tgts);

0
scripts/common/configs-downloading.sh Normal file → Executable file
View File

0
scripts/common/download_test_videos.sh Normal file → Executable file
View File

1
scripts/common/ffmpeg425-install.sh Normal file → Executable file
View File

@@ -17,6 +17,7 @@ cd nv-codec-headers
git checkout n11.1.5.0
sudo make install
cd ..
sudo rm -r nv-codec-headers
wget https://ffmpeg.org/releases/ffmpeg-4.2.5.tar.bz2
tar -xjf ffmpeg-4.2.5.tar.bz2

0
scripts/common/gst-install-orin.sh Normal file → Executable file
View File

0
scripts/common/gst-install.sh Normal file → Executable file
View File

0
scripts/common/models-converting.sh Normal file → Executable file
View File

28
scripts/common/models-downloading.sh Normal file → Executable file
View File

@@ -3,12 +3,6 @@
root_dir=${HOME}"/SpireCV/models"
root_server="https://download.amovlab.com/model"
sv_params1=${HOME}"/SpireCV/sv_algorithm_params.json"
sv_params2=${HOME}"/SpireCV/sv_algorithm_params_coco_640.json"
sv_params3=${HOME}"/SpireCV/sv_algorithm_params_coco_1280.json"
camera_params1=${HOME}"/SpireCV/calib_webcam_640x480.yaml"
camera_params2=${HOME}"/SpireCV/calib_webcam_1280x720.yaml"
coco_model1="COCO-yolov5s.wts"
coco_model2="COCO-yolov5s6.wts"
coco_model3="COCO-yolov5s-seg.wts"
@@ -46,28 +40,6 @@ if [ ! -d ${root_dir} ]; then
mkdir -p ${root_dir}
fi
if [ ! -f ${sv_params1} ]; then
echo -e "\033[32m[INFO]: ${sv_params1} not exist, downloading ... \033[0m"
wget -O ${sv_params1} ${root_server}/install/a-params/sv_algorithm_params.json
fi
if [ ! -f ${sv_params2} ]; then
echo -e "\033[32m[INFO]: ${sv_params2} not exist, downloading ... \033[0m"
wget -O ${sv_params2} ${root_server}/install/a-params/sv_algorithm_params_coco_640.json
fi
if [ ! -f ${sv_params3} ]; then
echo -e "\033[32m[INFO]: ${sv_params3} not exist, downloading ... \033[0m"
wget -O ${sv_params3} ${root_server}/install/a-params/sv_algorithm_params_coco_1280.json
fi
if [ ! -f ${camera_params1} ]; then
echo -e "\033[32m[INFO]: ${camera_params1} not exist, downloading ... \033[0m"
wget -O ${camera_params1} ${root_server}/install/c-params/calib_webcam_640x480.yaml
fi
if [ ! -f ${camera_params2} ]; then
echo -e "\033[32m[INFO]: ${camera_params2} not exist, downloading ... \033[0m"
wget -O ${camera_params2} ${root_server}/install/c-params/calib_webcam_1280x720.yaml
fi
if [ ! -f ${coco_model1_fn} ]; then
echo -e "\033[32m[INFO]: ${coco_model1_fn} not exist, downloading ... \033[0m"
wget -O ${coco_model1_fn} ${root_server}/install/${coco_model1}

0
scripts/common/opencv470-install.sh Normal file → Executable file
View File

View File

@@ -0,0 +1,39 @@
#!/bin/bash -e
root_dir=${HOME}"/SpireCV/models"
root_server="https://download.amovlab.com/model"
sv_params1=${HOME}"/SpireCV/sv_algorithm_params.json"
sv_params2=${HOME}"/SpireCV/sv_algorithm_params_coco_640.json"
sv_params3=${HOME}"/SpireCV/sv_algorithm_params_coco_1280.json"
camera_params1=${HOME}"/SpireCV/calib_webcam_640x480.yaml"
camera_params2=${HOME}"/SpireCV/calib_webcam_1280x720.yaml"
if [ ! -d ${root_dir} ]; then
echo -e "\033[32m[INFO]: ${root_dir} not exist, creating it ... \033[0m"
mkdir -p ${root_dir}
fi
if [ ! -f ${sv_params1} ]; then
echo -e "\033[32m[INFO]: ${sv_params1} not exist, downloading ... \033[0m"
wget -O ${sv_params1} ${root_server}/install/a-params/sv_algorithm_params.json
fi
if [ ! -f ${sv_params2} ]; then
echo -e "\033[32m[INFO]: ${sv_params2} not exist, downloading ... \033[0m"
wget -O ${sv_params2} ${root_server}/install/a-params/sv_algorithm_params_coco_640.json
fi
if [ ! -f ${sv_params3} ]; then
echo -e "\033[32m[INFO]: ${sv_params3} not exist, downloading ... \033[0m"
wget -O ${sv_params3} ${root_server}/install/a-params/sv_algorithm_params_coco_1280.json
fi
if [ ! -f ${camera_params1} ]; then
echo -e "\033[32m[INFO]: ${camera_params1} not exist, downloading ... \033[0m"
wget -O ${camera_params1} ${root_server}/install/c-params/calib_webcam_640x480.yaml
fi
if [ ! -f ${camera_params2} ]; then
echo -e "\033[32m[INFO]: ${camera_params2} not exist, downloading ... \033[0m"
wget -O ${camera_params2} ${root_server}/install/c-params/calib_webcam_1280x720.yaml
fi

View File

@@ -0,0 +1,24 @@
#!/bin/sh
sudo apt install -y libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev
sudo apt install -y libgstreamer-plugins-bad1.0-dev gstreamer1.0-plugins-base
sudo apt install -y gstreamer1.0-plugins-good gstreamer1.0-plugins-bad
sudo apt install -y gstreamer1.0-plugins-ugly gstreamer1.0-libav gstreamer1.0-doc
sudo apt install -y gstreamer1.0-tools gstreamer1.0-x gstreamer1.0-alsa
sudo apt install -y gstreamer1.0-gl gstreamer1.0-gtk3 gstreamer1.0-qt5
sudo apt install -y gstreamer1.0-pulseaudio
sudo apt install -y gtk-doc-tools
sudo apt install -y libeigen3-dev libfmt-dev v4l-utils
sudo apt -y install autotools-dev automake m4 perl
sudo apt -y install libtool
autoreconf -ivf
git clone https://gitee.com/jario-jin/gst-rtsp-server-b18.git
cd gst-rtsp-server-b18
./autogen.sh
make
sudo make install
cd ..
sudo rm -r gst-rtsp-server-b18

20
scripts/jetson/gst-install.sh Executable file
View File

@@ -0,0 +1,20 @@
#!/bin/sh
sudo apt install -y libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev
sudo apt install -y libgstreamer-plugins-bad1.0-dev gstreamer1.0-plugins-base
sudo apt install -y gstreamer1.0-plugins-good gstreamer1.0-plugins-bad
sudo apt install -y gstreamer1.0-plugins-ugly gstreamer1.0-libav gstreamer1.0-doc
sudo apt install -y gstreamer1.0-tools gstreamer1.0-x gstreamer1.0-alsa
sudo apt install -y gstreamer1.0-gl gstreamer1.0-gtk3 gstreamer1.0-qt5
sudo apt install -y gstreamer1.0-pulseaudio
sudo apt install -y gtk-doc-tools
sudo apt install -y libeigen3-dev libfmt-dev v4l-utils
git clone https://gitee.com/jario-jin/gst-rtsp-server-b18.git
cd gst-rtsp-server-b18
./autogen.sh
make
sudo make install
cd ..
sudo rm -r gst-rtsp-server-b18

View File

@@ -5,7 +5,7 @@ wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_cache_x86-4.7.0.zip
current_dir=$(pwd)
package_dir="."
mkdir ~/opencv_build
@@ -67,3 +67,4 @@ sudo make install
cd
sudo rm -r ~/opencv_build
cd ${current_dir}

3
scripts/jetson/opencv470-jetpack511-cuda-install.sh Normal file → Executable file
View File

@@ -5,7 +5,7 @@ wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_cache-4.7.0.zip
current_dir=$(pwd)
package_dir="."
mkdir ~/opencv_build
@@ -52,3 +52,4 @@ sudo make install
cd
sudo rm -r ~/opencv_build
cd ${current_dir}

3
scripts/jetson/opencv470-jetpack511-install.sh Normal file → Executable file
View File

@@ -5,7 +5,7 @@ wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_cache-4.7.0.zip
current_dir=$(pwd)
package_dir="."
mkdir ~/opencv_build
@@ -52,3 +52,4 @@ sudo make install
cd
sudo rm -r ~/opencv_build
cd ${current_dir}

119
scripts/model_sync.py Normal file
View File

@@ -0,0 +1,119 @@
#!/usr/bin/env python3
# -*- coding:utf-8 -*-
import os
import requests
import argparse
root_url = "https://download.amovlab.com/model/SpireCV-models/"
model_list_url = root_url + "model-list.txt"
root_path = os.path.expanduser("~") + "/SpireCV/models"
print("MODEL PATH:", root_path)
if not os.path.exists(root_path):
os.makedirs(root_path)
list_file = os.path.join(root_path, "model-list.txt")
def main():
parser = argparse.ArgumentParser(description="SpireCV Model SYNC")
parser.add_argument(
"-p", "--platform",
type=str,
required=True,
help="Supported Platforms: nv (Nvidia), int (Intel)",
)
args = parser.parse_args()
if args.platform in ['nv', 'nvidia', 'Nv', 'Nvidia']:
prefix = 'Nv'
elif args.platform in ['int', 'intel', 'Int', 'Intel']:
prefix = 'Int'
else:
raise Exception("Platform NOT Support!")
r = requests.get(model_list_url)
with open(list_file, "wb") as f:
f.write(r.content)
with open(list_file, 'r') as file:
lines = file.readlines()
need_switch = False
for line in lines:
line = line.strip()
if len(line) > 0:
model_file = os.path.join(root_path, line)
if not os.path.exists(model_file) and (line.startswith(prefix) or line.startswith('Ocv')):
print("[1] Downloading Model:", line, "...")
r = requests.get(root_url + line)
with open(model_file, "wb") as f:
f.write(r.content)
need_switch = True
if os.path.exists(model_file):
print("[1] Model:", line, "EXIST!")
if line.startswith('Nv'):
net = line.split('-')[2]
if net.startswith("yolov5"):
if len(net.split('_')) == 3:
name, seg, ncls = net.split('_')
engine_fn = os.path.splitext(model_file)[0].replace(net, name + "_" + seg + '_b1_' + ncls) + '.engine'
online_fn = os.path.splitext(model_file)[0].replace(net, name + "_" + seg + '_b1_' + ncls) + '-online.engine'
else:
name, ncls = net.split('_')
engine_fn = os.path.splitext(model_file)[0].replace(net, name + '_b1_' + ncls) + '.engine'
online_fn = os.path.splitext(model_file)[0].replace(net, name + '_b1_' + ncls) + '-online.engine'
else:
engine_fn = os.path.splitext(model_file)[0] + '.engine'
online_fn = os.path.splitext(model_file)[0] + '-online.engine'
if not os.path.exists(engine_fn) and not os.path.exists(online_fn):
if net.startswith("yolov5"):
if len(net.split('_')) == 3:
name, seg, ncls = net.split('_')
cmd = "SpireCVSeg -s {} {} {} {}".format(
model_file, engine_fn, ncls[1:], name[6:]
)
else:
name, ncls = net.split('_')
cmd = "SpireCVDet -s {} {} {} {}".format(
model_file, engine_fn, ncls[1:], name[6:]
)
elif line.endswith("onnx"):
cmd = ("/usr/src/tensorrt/bin/trtexec --explicitBatch --onnx={} "
"--saveEngine={} --fp16").format(
model_file, engine_fn
)
print(" [2] Converting Model:", line, "->", engine_fn, "...")
result = os.popen(cmd).read()
need_switch = True
else:
print(" [2] Model Converting FINISH!")
model_file = engine_fn
if not line.startswith('Ocv') and need_switch:
ext = os.path.splitext(model_file)[1]
fn_prefix = '-'.join(os.path.basename(model_file).split('-')[:3])
file_names = os.listdir(root_path)
selected = []
for file_name in file_names:
if file_name.startswith(fn_prefix) and file_name.endswith(ext):
selected.append(file_name)
if len(selected) > 0:
for i, sel in enumerate(selected):
if sel.endswith('-online' + ext):
os.rename(
os.path.join(root_path, sel),
os.path.join(root_path, '-'.join(sel.split('-')[:4])) + ext
)
selected[i] = '-'.join(sel.split('-')[:4]) + ext
selected.sort(reverse=True)
os.rename(
os.path.join(root_path, selected[0]),
os.path.join(root_path, os.path.splitext(selected[0])[0] + "-online" + ext)
)
online_model = os.path.splitext(selected[0])[0] + "-online" + ext
print(" [3] Model {} ONLINE *".format(online_model))
if __name__ == "__main__":
main()

View File

@@ -0,0 +1,39 @@
#!/bin/bash -e
root_dir=${HOME}"/SpireCV/models"
root_server="https://download.amovlab.com/model"
sv_params1=${HOME}"/SpireCV/sv_algorithm_params.json"
sv_params2=${HOME}"/SpireCV/sv_algorithm_params_coco_640.json"
sv_params3=${HOME}"/SpireCV/sv_algorithm_params_coco_1280.json"
camera_params1=${HOME}"/SpireCV/calib_webcam_640x480.yaml"
camera_params2=${HOME}"/SpireCV/calib_webcam_1280x720.yaml"
if [ ! -d ${root_dir} ]; then
echo -e "\033[32m[INFO]: ${root_dir} not exist, creating it ... \033[0m"
mkdir -p ${root_dir}
fi
if [ ! -f ${sv_params1} ]; then
echo -e "\033[32m[INFO]: ${sv_params1} not exist, downloading ... \033[0m"
wget -O ${sv_params1} ${root_server}/install/a-params/sv_algorithm_params.json
fi
if [ ! -f ${sv_params2} ]; then
echo -e "\033[32m[INFO]: ${sv_params2} not exist, downloading ... \033[0m"
wget -O ${sv_params2} ${root_server}/install/a-params/sv_algorithm_params_coco_640.json
fi
if [ ! -f ${sv_params3} ]; then
echo -e "\033[32m[INFO]: ${sv_params3} not exist, downloading ... \033[0m"
wget -O ${sv_params3} ${root_server}/install/a-params/sv_algorithm_params_coco_1280.json
fi
if [ ! -f ${camera_params1} ]; then
echo -e "\033[32m[INFO]: ${camera_params1} not exist, downloading ... \033[0m"
wget -O ${camera_params1} ${root_server}/install/c-params/calib_webcam_640x480.yaml
fi
if [ ! -f ${camera_params2} ]; then
echo -e "\033[32m[INFO]: ${camera_params2} not exist, downloading ... \033[0m"
wget -O ${camera_params2} ${root_server}/install/c-params/calib_webcam_1280x720.yaml
fi

View File

@@ -0,0 +1,66 @@
#!/bin/sh
sudo apt install -y \
build-essential yasm cmake libtool libc6 libc6-dev unzip wget libeigen3-dev libfmt-dev \
libnuma1 libnuma-dev libx264-dev libx265-dev libfaac-dev libssl-dev v4l-utils
current_dir=$(pwd)
root_dir=${HOME}"/SpireCV"
if [ ! -d ${root_dir} ]; then
echo -e "\033[32m[INFO]: ${root_dir} not exist, creating it ... \033[0m"
mkdir -p ${root_dir}
fi
cd ${root_dir}
git clone https://gitee.com/jario-jin/nv-codec-headers.git
cd nv-codec-headers
git checkout n11.1.5.0
sudo make install
cd ..
sudo rm -r nv-codec-headers
wget https://ffmpeg.org/releases/ffmpeg-4.2.5.tar.bz2
tar -xjf ffmpeg-4.2.5.tar.bz2
cd ffmpeg-4.2.5
export PATH=$PATH:/usr/local/cuda/bin
sed -i 's#_30#_75#' configure; sed -i 's#_30#_75#' configure
./configure \
--enable-nonfree \
--enable-gpl \
--enable-shared \
--enable-ffmpeg \
--enable-ffplay \
--enable-ffprobe \
--enable-libx264 \
--enable-libx265 \
--enable-cuda-nvcc \
--enable-nvenc \
--enable-cuda \
--enable-cuvid \
--enable-libnpp \
--extra-libs="-lpthread -lm" \
--extra-cflags=-I/usr/local/cuda/include \
--extra-ldflags=-L/usr/local/cuda/lib64
make -j8
sudo make install
cd ..
git clone https://gitee.com/jario-jin/ZLMediaKit.git
cd ZLMediaKit
git submodule update --init
mkdir build
cd build
cmake ..
make -j4
cd ..
cd ..
mkdir ZLM
cd ZLM
cp ../ZLMediaKit/release/linux/Debug/MediaServer .
cp ../ZLMediaKit/release/linux/Debug/config.ini .
cd ..
cd ${current_dir}

View File

@@ -5,7 +5,7 @@ wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_cache_x86-4.7.0.zip
current_dir=$(pwd)
package_dir="."
mkdir ~/opencv_build
@@ -67,3 +67,4 @@ sudo make install
cd
sudo rm -r ~/opencv_build
cd ${current_dir}

View File

@@ -0,0 +1,70 @@
#!/bin/sh
wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_cache_x86-4.7.0.zip
current_dir=$(pwd)
package_dir="."
mkdir ~/opencv_build
if [ ! -d ""$package_dir"" ];then
echo "\033[31m[ERROR]: $package_dir not exist!: \033[0m"
exit 1
fi
# sudo add-apt-repository "deb http://security.ubuntu.com/ubuntu xenial-security main"
# sudo add-apt-repository "deb http://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial main multiverse restricted universe"
sudo apt update
sudo apt install -y build-essential
sudo apt install -y cmake git libgtk2.0-dev pkg-config libavcodec-dev libavformat-dev libswscale-dev
sudo add-apt-repository "deb http://security.ubuntu.com/ubuntu xenial-security main"
sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 3B4FE6ACC0B21F32
sudo apt update
sudo apt install -y libjasper1 libjasper-dev
sudo apt install -y python3-dev python3-numpy libtbb2 libtbb-dev libjpeg-dev libpng-dev libtiff-dev
sudo apt install -y libdc1394-22-dev
sudo apt install -y libcurl4 build-essential pkg-config cmake libopenblas-dev libeigen3-dev \
libtbb-dev libavcodec-dev libavformat-dev libgstreamer-plugins-base1.0-dev \
libgstreamer1.0-dev libswscale-dev libgtk-3-dev libpng-dev libjpeg-dev \
libcanberra-gtk-module libcanberra-gtk3-module
echo "\033[32m[INFO]:\033[0m unzip opencv-4.7.0.zip ..."
unzip -q -o $package_dir/opencv-4.7.0.zip -d ~/opencv_build
echo "\033[32m[INFO]:\033[0m unzip opencv_contrib-4.7.0.zip ..."
unzip -q -o $package_dir/opencv_contrib-4.7.0.zip -d ~/opencv_build
echo "\033[32m[INFO]:\033[0m unzip opencv_cache_x86-4.7.0.zip ..."
unzip -q -o $package_dir/opencv_cache_x86-4.7.0.zip -d ~/opencv_build
sudo rm opencv-4.7.0.zip
sudo rm opencv_contrib-4.7.0.zip
sudo rm opencv_cache_x86-4.7.0.zip
cd ~/opencv_build/opencv-4.7.0
mkdir .cache
cp -r ~/opencv_build/opencv_cache_x86-4.7.0/* ~/opencv_build/opencv-4.7.0/.cache/
mkdir build
cd build
cmake -D CMAKE_BUILD_TYPE=Release \
-D WITH_CUDA=OFF \
-D OPENCV_ENABLE_NONFREE=ON \
-D CMAKE_INSTALL_PREFIX=/usr/local \
-D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules ..
make -j2
sudo make install
cd
sudo rm -r ~/opencv_build
cd ${current_dir}

View File

@@ -0,0 +1,95 @@
#!/bin/sh
echo "\033[32m[INFO]:\033[0m Please enter the folder path of the installation package: "
# package_dir="/home/jario/Downloads/nv"
wget https://download.amovlab.com/model/install/x86-nvidia/cuda-repo-ubuntu1804-11-1-local_11.1.1-455.32.00-1_amd64.deb
wget https://download.amovlab.com/model/install/x86-nvidia/cudnn-11.3-linux-x64-v8.2.1.32.tgz
wget https://download.amovlab.com/model/install/x86-nvidia/nv-tensorrt-repo-ubuntu1804-cuda11.3-trt8.0.1.6-ga-20210626_1-1_amd64.deb
wget https://download.amovlab.com/model/install/x86-nvidia/cuda-ubuntu1804.pin
package_dir="."
cuda_fn=$package_dir"/cuda-repo-ubuntu1804-11-1-local_11.1.1-455.32.00-1_amd64.deb"
cudnn_fn=$package_dir"/cudnn-11.3-linux-x64-v8.2.1.32.tgz"
tensorrt_fn=$package_dir"/nv-tensorrt-repo-ubuntu1804-cuda11.3-trt8.0.1.6-ga-20210626_1-1_amd64.deb"
tmp_dir="/tmp"
echo "\033[32m[INFO]: CUDA_PKG: \033[0m"$cuda_fn
echo "\033[32m[INFO]: CUDNN_PKG: \033[0m"$cudnn_fn
echo "\033[32m[INFO]: TENSORRT_PKG: \033[0m"$tensorrt_fn
# 所有文件都存在时,才会继续执行脚本
if [ ! -f "$cuda_fn" ]; then
echo "\033[31m[ERROR]: CUDA_PKG not exist!: \033[0m"
exit 1
fi
if [ ! -f "$cudnn_fn" ]; then
echo "\033[31m[ERROR]: CUDNN_PKG not exist!: \033[0m"
exit 1
fi
if [ ! -f "$tensorrt_fn" ]; then
echo "\033[31m[ERROR]: TENSORRT_PKG not exist!: \033[0m"
exit 1
fi
# 删除显卡驱动
# sudo apt-get remove nvidia-*
# 安装显卡驱动
# echo "\033[32m[INFO]: Nvidia Driver installing ...\033[0m"
# ubuntu-drivers devices
# sudo ubuntu-drivers autoinstall
# 删除已安装CUDA
# --purge选项会将配置文件、数据库等删除
# sudo apt-get autoremove --purge cuda
# 查看安装了哪些cuda相关的库可以用以下指令
# sudo dpkg -l |grep cuda
# sudo dpkg -P cuda-repo-ubuntu1804-10-2-local-10.2.89-440.33.01
# sudo dpkg -P cuda-repo-ubuntu1804-11-1-local
# sudo dpkg -P nv-tensorrt-repo-ubuntu1804-cuda10.2-trt8.0.1.6-ga-20210626
# 这个key值是官网文档查到的当然通过apt-key list也能查看
# sudo apt-key list
# sudo apt-key del 7fa2af80
# 安装CUDA
echo "\033[32m[INFO]: CUDA installing ...\033[0m"
# wget https://developer.download.nvidia.com/compute/cuda/repos/ubuntu1804/x86_64/cuda-ubuntu1804.pin
sudo cp $package_dir/cuda-ubuntu1804.pin /etc/apt/preferences.d/cuda-repository-pin-600
sudo dpkg -i $cuda_fn
sudo apt-key add /var/cuda-repo-ubuntu1804-11-1-local/7fa2af80.pub
sudo apt-get update
sudo apt-get -y install cuda
# 安装CUDNN
echo "\033[32m[INFO]: CUDNN installing ...\033[0m"
tar zxvf $cudnn_fn -C $tmp_dir
sudo cp $tmp_dir/cuda/include/cudnn* /usr/local/cuda/include/
sudo cp $tmp_dir/cuda/lib64/libcudnn* /usr/local/cuda/lib64/
sudo chmod a+r /usr/local/cuda/include/cudnn* /usr/local/cuda/lib64/libcudnn*
sudo ln -sf /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_cnn_infer.so.8.2.1 /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_cnn_infer.so.8
sudo ln -sf /usr/local/cuda/targets/x86_64-linux/lib/libcudnn.so.8.2.1 /usr/local/cuda/targets/x86_64-linux/lib/libcudnn.so.8
sudo ln -sf /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_ops_train.so.8.2.1 /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_ops_train.so.8
sudo ln -sf /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_adv_train.so.8.2.1 /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_adv_train.so.8
sudo ln -sf /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_ops_infer.so.8.2.1 /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_ops_infer.so.8
sudo ln -sf /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_cnn_train.so.8.2.1 /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_cnn_train.so.8
sudo ln -sf /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_adv_infer.so.8.2.1 /usr/local/cuda/targets/x86_64-linux/lib/libcudnn_adv_infer.so.8
# 安装TensorRT
sudo dpkg -i $tensorrt_fn
sudo apt-key add /var/nv-tensorrt-repo-cuda11.3-trt8.0.1.6-ga-20210626/7fa2af80.pub
sudo apt-get update
sudo apt-get install tensorrt -y
sudo apt-get install python3-libnvinfer-dev -y
sudo rm $cuda_fn
sudo rm $cudnn_fn
sudo rm $tensorrt_fn
sudo rm cuda-ubuntu1804.pin

View File

@@ -0,0 +1,39 @@
#!/bin/bash -e
root_dir=${HOME}"/SpireCV/models"
root_server="https://download.amovlab.com/model"
sv_params1=${HOME}"/SpireCV/sv_algorithm_params.json"
sv_params2=${HOME}"/SpireCV/sv_algorithm_params_coco_640.json"
sv_params3=${HOME}"/SpireCV/sv_algorithm_params_coco_1280.json"
camera_params1=${HOME}"/SpireCV/calib_webcam_640x480.yaml"
camera_params2=${HOME}"/SpireCV/calib_webcam_1280x720.yaml"
if [ ! -d ${root_dir} ]; then
echo -e "\033[32m[INFO]: ${root_dir} not exist, creating it ... \033[0m"
mkdir -p ${root_dir}
fi
if [ ! -f ${sv_params1} ]; then
echo -e "\033[32m[INFO]: ${sv_params1} not exist, downloading ... \033[0m"
wget -O ${sv_params1} ${root_server}/install/a-params/sv_algorithm_params.json
fi
if [ ! -f ${sv_params2} ]; then
echo -e "\033[32m[INFO]: ${sv_params2} not exist, downloading ... \033[0m"
wget -O ${sv_params2} ${root_server}/install/a-params/sv_algorithm_params_coco_640.json
fi
if [ ! -f ${sv_params3} ]; then
echo -e "\033[32m[INFO]: ${sv_params3} not exist, downloading ... \033[0m"
wget -O ${sv_params3} ${root_server}/install/a-params/sv_algorithm_params_coco_1280.json
fi
if [ ! -f ${camera_params1} ]; then
echo -e "\033[32m[INFO]: ${camera_params1} not exist, downloading ... \033[0m"
wget -O ${camera_params1} ${root_server}/install/c-params/calib_webcam_640x480.yaml
fi
if [ ! -f ${camera_params2} ]; then
echo -e "\033[32m[INFO]: ${camera_params2} not exist, downloading ... \033[0m"
wget -O ${camera_params2} ${root_server}/install/c-params/calib_webcam_1280x720.yaml
fi

View File

@@ -0,0 +1,26 @@
#!/bin/sh
sudo apt install -y v4l-utils build-essential yasm cmake libtool libc6 libc6-dev unzip wget libeigen3-dev libfmt-dev libnuma1 libnuma-dev libx264-dev libx265-dev libfaac-dev libssl-dev v4l-utils
wget https://ffmpeg.org/releases/ffmpeg-4.2.5.tar.bz2
tar -xjf ffmpeg-4.2.5.tar.bz2
cd ffmpeg-4.2.5
./configure \
--arch=x86_64 \
--disable-x86asm \
--enable-vaapi \
--enable-libmfx \
--enable-nonfree \
--enable-shared \
--enable-ffmpeg \
--enable-ffplay \
--enable-ffprobe \
--enable-libx264 \
--enable-libx265 \
--enable-gpl
make -j8
sudo make install
cd ..
sudo rm -r ffmpeg-4.2.5
sudo rm ffmpeg-4.2.5.tar.bz2

View File

@@ -0,0 +1,6 @@
#!/bin/sh
sudo apt-get install -y libmfx1 libmfx-tools libva-dev libmfx-dev intel-media-va-driver-non-free vainfo
echo "export LIBVA_DRIVER_NAME=iHD" >> ~/.bashrc
export LIBVA_DRIVER_NAME=iHD

View File

@@ -0,0 +1,7 @@
#!/bin/sh
curl -L https://repositories.intel.com/graphics/intel-graphics.key | sudo apt-key add -
sudo apt-add-repository 'deb [arch=amd64] https://repositories.intel.com/graphics/ubuntu focal main'
sudo apt-get update
sudo apt-get install -y -q --no-install-recommends clinfo intel-opencl-icd intel-media-va-driver-non-free

View File

@@ -0,0 +1,70 @@
#!/bin/sh
wget https://download.amovlab.com/model/deps/opencv-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_contrib-4.7.0.zip
wget https://download.amovlab.com/model/deps/opencv_cache_x86-4.7.0.zip
current_dir=$(pwd)
package_dir="."
mkdir ~/opencv_build
if [ ! -d ""$package_dir"" ];then
echo "\033[31m[ERROR]: $package_dir not exist!: \033[0m"
exit 1
fi
# sudo add-apt-repository "deb http://security.ubuntu.com/ubuntu xenial-security main"
# sudo add-apt-repository "deb http://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial main multiverse restricted universe"
sudo apt update
sudo apt install -y build-essential
sudo apt install -y cmake git libgtk2.0-dev pkg-config libavcodec-dev libavformat-dev libswscale-dev
sudo add-apt-repository "deb http://security.ubuntu.com/ubuntu xenial-security main"
sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 3B4FE6ACC0B21F32
sudo apt update
sudo apt install -y libjasper1 libjasper-dev
sudo apt install -y python3-dev python3-numpy libtbb2 libtbb-dev libjpeg-dev libpng-dev libtiff-dev
sudo apt install -y libdc1394-22-dev
sudo apt install -y libcurl4 build-essential pkg-config cmake libopenblas-dev libeigen3-dev \
libtbb-dev libavcodec-dev libavformat-dev libgstreamer-plugins-base1.0-dev \
libgstreamer1.0-dev libswscale-dev libgtk-3-dev libpng-dev libjpeg-dev \
libcanberra-gtk-module libcanberra-gtk3-module
echo "\033[32m[INFO]:\033[0m unzip opencv-4.7.0.zip ..."
unzip -q -o $package_dir/opencv-4.7.0.zip -d ~/opencv_build
echo "\033[32m[INFO]:\033[0m unzip opencv_contrib-4.7.0.zip ..."
unzip -q -o $package_dir/opencv_contrib-4.7.0.zip -d ~/opencv_build
echo "\033[32m[INFO]:\033[0m unzip opencv_cache_x86-4.7.0.zip ..."
unzip -q -o $package_dir/opencv_cache_x86-4.7.0.zip -d ~/opencv_build
sudo rm opencv-4.7.0.zip
sudo rm opencv_contrib-4.7.0.zip
sudo rm opencv_cache_x86-4.7.0.zip
cd ~/opencv_build/opencv-4.7.0
mkdir .cache
cp -r ~/opencv_build/opencv_cache_x86-4.7.0/* ~/opencv_build/opencv-4.7.0/.cache/
mkdir build
cd build
cmake -D CMAKE_BUILD_TYPE=Release \
-D WITH_CUDA=OFF \
-D OPENCV_ENABLE_NONFREE=ON \
-D CMAKE_INSTALL_PREFIX=/usr/local \
-D OPENCV_EXTRA_MODULES_PATH=../../opencv_contrib-4.7.0/modules ..
make -j2
sudo make install
cd
sudo rm -r ~/opencv_build
cd ${current_dir}

View File

@@ -0,0 +1,20 @@
#!/bin/sh
sudo mkdir /opt/intel
current_dir=$(pwd)
cd ${HOME}/Downloads
curl -L https://storage.openvinotoolkit.org/repositories/openvino/packages/2022.3.1/linux/l_openvino_toolkit_ubuntu20_2022.3.1.9227.cf2c7da5689_x86_64.tgz --output openvino_2022.3.1.tgz
tar -xf openvino_2022.3.1.tgz
sudo mv l_openvino_toolkit_ubuntu20_2022.3.1.9227.cf2c7da5689_x86_64 /opt/intel/openvino_2022.3.1
cd /opt/intel/openvino_2022.3.1
sudo -E ./install_dependencies/install_openvino_dependencies.sh
cd /opt/intel
sudo ln -s openvino_2022.3.1 openvino_2022
echo "source /opt/intel/openvino_2022/setupvars.sh" >> ~/.bashrc
sh /opt/intel/openvino_2022/setupvars.sh
cd ${current_dir}

View File

@@ -0,0 +1,22 @@
#!/bin/sh
current_dir=$(pwd)
cd ${HOME}/SpireCV
git clone https://gitee.com/jario-jin/ZLMediaKit.git
cd ZLMediaKit
git submodule update --init
mkdir build
cd build
cmake ..
make -j4
cd ..
cd ..
mkdir ZLM
cd ZLM
cp ../ZLMediaKit/release/linux/Debug/MediaServer .
cp ../ZLMediaKit/release/linux/Debug/config.ini .
cd ${current_dir}

View File

@@ -379,7 +379,7 @@ void _load_all_json(std::string json_fn, JsonValue& value, JsonAllocator& alloca
}
fin.close();
// std::cout << json_str << std::endl;
char source[1024 * 1024]; // 1M
char source[1024 * 256]; // 256K
char *endptr;
strcpy(source, json_str.c_str());

View File

@@ -6,6 +6,10 @@
#include <ctime>
#include <chrono>
#include <fstream>
#include <dirent.h>
#include <opencv2/opencv.hpp>
#include <unordered_map>
using namespace std;
@@ -25,6 +29,15 @@ bool _is_file_exist(std::string& fn)
return f.good();
}
bool _comp_str_greater(const std::string& a, const std::string& b)
{
return a > b;
}
bool _comp_str_lesser(const std::string& a, const std::string& b)
{
return a < b;
}
void _get_sys_time(TimeInfo& t_info)
{
@@ -136,4 +149,56 @@ int _comp_str_idx(const std::string& in_str, const std::string* str_list, int le
return -1;
}
void _list_dir(std::string dir, std::vector<std::string>& files, std::string suffixs, std::string prefix, bool r) {
// assert(_endswith(dir, "/") || _endswith(dir, "\\"));
DIR *pdir;
struct dirent *ent;
string childpath;
string absolutepath;
pdir = opendir(dir.c_str());
assert(pdir != NULL);
vector<string> suffixd(0);
if (!suffixs.empty() && suffixs != "") {
suffixd = _split(suffixs, "|");
}
while ((ent = readdir(pdir)) != NULL) {
if (ent->d_type & DT_DIR) {
if (strcmp(ent->d_name, ".") == 0 || strcmp(ent->d_name, "..") == 0) {
continue;
}
if (r) { // If need to traverse subdirectories
childpath = dir + ent->d_name;
_list_dir(childpath, files);
}
}
else {
if (suffixd.size() > 0) {
bool can_push = false, cancan_push = true;
for (int i = 0; i < (int)suffixd.size(); i++) {
if (_endswith(ent->d_name, suffixd[i]))
can_push = true;
}
if (prefix.size() > 0) {
if (!_startswith(ent->d_name, prefix))
cancan_push = false;
}
if (can_push && cancan_push) {
absolutepath = dir + ent->d_name;
files.push_back(ent->d_name); // filepath
}
}
else {
absolutepath = dir + ent->d_name;
files.push_back(ent->d_name); // filepath
}
}
}
sort(files.begin(), files.end()); //sort names
}
}

View File

@@ -24,10 +24,13 @@ bool _startswith(const std::string& str, const std::string& start);
bool _endswith(const std::string& str, const std::string& end);
std::string _trim(const std::string& str);
int _comp_str_idx(const std::string& in_str, const std::string* str_list, int len);
bool _comp_str_greater(const std::string& a, const std::string& b);
bool _comp_str_lesser(const std::string& a, const std::string& b);
/************* file-related functions ***************/
std::string _get_home();
bool _is_file_exist(std::string& fn);
void _list_dir(std::string dir, std::vector<std::string>& files, std::string suffixs="", std::string prefix="", bool r=false);
}

View File

@@ -0,0 +1,50 @@
#pragma once
#include <string>
#include <vector>
#include <chrono>
// 获取当前系统启动以来的毫秒数
static int64_t getCurTime()
{
// tv_sec (s) tv_nsec (ns-纳秒)
struct timespec now;
clock_gettime(CLOCK_MONOTONIC, &now);
return (now.tv_sec * 1000 + now.tv_nsec / 1000000);
}
struct VideoFrame
{
public:
enum VideoFrameType
{
BGR = 0,
RGB ,
YUV420P,
};
// VideoFrame(VideoFrameType type, int width, int height,int size)
VideoFrame(VideoFrameType type, int width, int height)
{
this->type = type;
this->width = width;
this->height = height;
this->size = width*height*3;
this->data = new uint8_t[this->size];
}
~VideoFrame()
{
delete[] this->data;
this->data = nullptr;
}
VideoFrameType type;
int size;
int width;
int height;
uint8_t *data;
};

View File

@@ -0,0 +1,635 @@
#include "bs_push_streamer.h"
/*
amov_rtsp
2914e3c44737811096c5e1797fe5373d12fcdd39
*/
// char av_error[AV_ERROR_MAX_STRING_SIZE] = { 0 };
// #define av_err2str(errnum) av_make_error_string(av_error, AV_ERROR_MAX_STRING_SIZE, errnum)
BsPushStreamer::BsPushStreamer()
{
}
BsPushStreamer::~BsPushStreamer()
{
mThread->join();
mThread = nullptr;
}
static int set_hwframe_ctx(AVCodecContext *ctx, AVBufferRef *hw_device_ctx, int width, int height)
{
AVBufferRef *hw_frames_ref;
AVHWFramesContext *frames_ctx = NULL;
int err = 0;
if (!(hw_frames_ref = av_hwframe_ctx_alloc(hw_device_ctx)))
{
fprintf(stderr, "Failed to create VAAPI frame context.\n");
return -1;
}
frames_ctx = (AVHWFramesContext *)(hw_frames_ref->data);
frames_ctx->format = AV_PIX_FMT_VAAPI;
frames_ctx->sw_format = AV_PIX_FMT_NV12;
frames_ctx->width = width;
frames_ctx->height = height;
frames_ctx->initial_pool_size = 20;
if ((err = av_hwframe_ctx_init(hw_frames_ref)) < 0)
{
// fprintf(stderr, "Failed to initialize VAAPI frame context."
// "Error code: %s\n",av_err2str(err));
av_buffer_unref(&hw_frames_ref);
return err;
}
ctx->hw_frames_ctx = av_buffer_ref(hw_frames_ref);
if (!ctx->hw_frames_ctx)
err = AVERROR(ENOMEM);
av_buffer_unref(&hw_frames_ref);
return err;
}
bool BsPushStreamer::setup(std::string name, int width, int height, int fps, std::string encoder, int bitrate = 4)
{
if (!connect(name, width, height, fps, encoder, bitrate))
{
std::cout << "BsPushStreamer::setup error\n";
return false;
}
mVideoFrame = new VideoFrame(VideoFrame::BGR, width, height);
// std::cout << "BsStreamer::setup Success!\n";
start();
return true;
}
void BsPushStreamer::start()
{
mThread = new std::thread(BsPushStreamer::encodeVideoAndWriteStreamThread, this);
mThread->native_handle();
push_running = true;
}
bool BsPushStreamer::connect(std::string name, int width, int height, int fps, std::string encoder, int bitrate)
{
// 初始化上下文
if (avformat_alloc_output_context2(&mFmtCtx, NULL, "rtsp", name.c_str()) < 0)
{
std::cout << "avformat_alloc_output_context2 error\n";
return false;
}
// 初始化视频编码器
// AVCodec *videoCodec = avcodec_find_encoder(AV_CODEC_ID_H264);
// AVCodec *videoCodec = avcodec_find_encoder_by_name("h264_nvenc");
err = av_hwdevice_ctx_create(&hw_device_ctx, AV_HWDEVICE_TYPE_VAAPI,
NULL, NULL, 0);
AVCodec *videoCodec = avcodec_find_encoder_by_name(encoder.c_str());
if (!videoCodec)
{
// std::cout << fmt::format("Using encoder:[{}] error!\n", encoder);
videoCodec = avcodec_find_encoder(AV_CODEC_ID_H264);
if (!videoCodec)
{
std::cout << "avcodec_alloc_context3 error";
return false;
}
std::cout << "Using default H264 encoder!\n";
}
mVideoCodecCtx = avcodec_alloc_context3(videoCodec);
if (!mVideoCodecCtx)
{
std::cout << "avcodec_alloc_context3 error";
return false;
}
// 压缩视频bit位大小 300kB
int bit_rate = bitrate * 1024 * 1024 * 8;
// CBRConstant BitRate - 固定比特率
mVideoCodecCtx->flags |= AV_CODEC_FLAG_QSCALE;
mVideoCodecCtx->bit_rate = bit_rate;
mVideoCodecCtx->rc_min_rate = bit_rate;
mVideoCodecCtx->rc_max_rate = bit_rate;
mVideoCodecCtx->bit_rate_tolerance = bit_rate;
mVideoCodecCtx->codec_id = videoCodec->id;
// 不支持AV_PIX_FMT_BGR24直接进行编码
mVideoCodecCtx->pix_fmt = AV_PIX_FMT_VAAPI;
mVideoCodecCtx->codec_type = AVMEDIA_TYPE_VIDEO;
mVideoCodecCtx->width = width;
mVideoCodecCtx->height = height;
mVideoCodecCtx->time_base = {1, fps};
mVideoCodecCtx->framerate = {fps, 1};
mVideoCodecCtx->gop_size = 12;
mVideoCodecCtx->max_b_frames = 0;
mVideoCodecCtx->thread_count = 1;
mVideoCodecCtx->sample_aspect_ratio = (AVRational){1, 1};
// 手动设置PPS
// unsigned char sps_pps[] = {
// 0x00, 0x00, 0x01, 0x67, 0x42, 0x00, 0x2a, 0x96, 0x35, 0x40, 0xf0, 0x04,
// 0x4f, 0xcb, 0x37, 0x01, 0x01, 0x01, 0x40, 0x00, 0x01, 0xc2, 0x00, 0x00, 0x57,
// 0xe4, 0x01, 0x00, 0x00, 0x00, 0x01, 0x68, 0xce, 0x3c, 0x80, 0x00
// };
AVDictionary *video_codec_options = NULL;
av_dict_set(&video_codec_options, "profile", "main", 0);
// av_dict_set(&video_codec_options, "preset", "superfast", 0);
av_dict_set(&video_codec_options, "tune", "fastdecode", 0);
if ((err = set_hwframe_ctx(mVideoCodecCtx, hw_device_ctx, width, height)) < 0)
{
std::cout << "set_hwframe_ctx error\n";
return false;
}
if (avcodec_open2(mVideoCodecCtx, videoCodec, &video_codec_options) < 0)
{
std::cout << "avcodec_open2 error\n";
return false;
}
mVideoStream = avformat_new_stream(mFmtCtx, videoCodec);
if (!mVideoStream)
{
std::cout << "avformat_new_stream error\n";
return false;
}
mVideoStream->id = mFmtCtx->nb_streams - 1;
// stream的time_base参数非常重要它表示将现实中的一秒钟分为多少个时间基, 在下面调用avformat_write_header时自动完成
avcodec_parameters_from_context(mVideoStream->codecpar, mVideoCodecCtx);
mVideoIndex = mVideoStream->id;
// open output url
av_dump_format(mFmtCtx, 0, name.c_str(), 1);
if (!(mFmtCtx->oformat->flags & AVFMT_NOFILE))
{
int ret = avio_open(&mFmtCtx->pb, name.c_str(), AVIO_FLAG_WRITE);
if (ret < 0)
{
// std::cout << fmt::format("avio_open error url: {}\n", name.c_str());
// std::cout << fmt::format("ret = {} : {}\n", ret, av_err2str(ret));
// std::cout << fmt::format("ret = {}\n", ret);
return false;
}
}
AVDictionary *fmt_options = NULL;
av_dict_set(&fmt_options, "bufsize", "1024", 0);
av_dict_set(&fmt_options, "rw_timeout", "30000000", 0); // 设置rtmp/http-flv连接超时单位 us
av_dict_set(&fmt_options, "stimeout", "30000000", 0); // 设置rtsp连接超时单位 us
av_dict_set(&fmt_options, "rtsp_transport", "tcp", 0);
mFmtCtx->video_codec_id = mFmtCtx->oformat->video_codec;
mFmtCtx->audio_codec_id = mFmtCtx->oformat->audio_codec;
// 调用该函数会将所有stream的time_base自动设置一个值通常是1/90000或1/1000这表示一秒钟表示的时间基长度
if (avformat_write_header(mFmtCtx, &fmt_options) < 0)
{
std::cout << "avformat_write_header error\n";
return false;
}
return true;
}
void BsPushStreamer::encodeVideoAndWriteStreamThread(void *arg)
{
// PushExecutor *executor = (PushExecutor *)arg;
BsPushStreamer *mBsPushStreamer = (BsPushStreamer *)arg;
int width = mBsPushStreamer->mVideoFrame->width;
int height = mBsPushStreamer->mVideoFrame->height;
// 未编码的视频帧bgr格式
// VideoFrame *videoFrame = NULL;
// 未编码视频帧队列当前长度
// int videoFrameQSize = 0;
AVFrame *hw_frame = NULL;
AVFrame *frame_nv12 = av_frame_alloc();
frame_nv12->format = AV_PIX_FMT_NV12;
frame_nv12->width = width;
frame_nv12->height = height;
int frame_nv12_buff_size = av_image_get_buffer_size(AV_PIX_FMT_NV12, width, height, 1);
uint8_t *frame_nv12_buff = (uint8_t *)av_malloc(frame_nv12_buff_size);
av_image_fill_arrays(
frame_nv12->data, frame_nv12->linesize,
frame_nv12_buff,
AV_PIX_FMT_NV12,
width, height, 1);
if (!(hw_frame = av_frame_alloc()))
{
std::cout << "Error while av_frame_alloc().\n";
}
if (av_hwframe_get_buffer(mBsPushStreamer->mVideoCodecCtx->hw_frames_ctx, hw_frame, 0) < 0)
{
std::cout << "Error while av_hwframe_get_buffer.\n";
}
if (!hw_frame->hw_frames_ctx)
{
std::cout << "Error while hw_frames_ctx.\n";
}
// 编码后的视频帧
AVPacket *pkt = av_packet_alloc();
int64_t encodeSuccessCount = 0;
int64_t frameCount = 0;
int64_t t1 = 0;
int64_t t2 = 0;
int ret = -1;
auto cnt_time = std::chrono::system_clock::now().time_since_epoch();
auto last_update_time = std::chrono::system_clock::now().time_since_epoch();
while (mBsPushStreamer->push_running)
{
// if (mBsPushStreamer->getVideoFrame(videoFrame, videoFrameQSize))
if (mBsPushStreamer->nd_push_frame)
{
mBsPushStreamer->nd_push_frame = false;
// frame_bgr 转 frame_nv12
//mBsPushStreamer->bgr24ToYuv420p(mBsPushStreamer->mVideoFrame->data, width, height, frame_nv12_buff);
mBsPushStreamer->Rgb2NV12(mBsPushStreamer->mVideoFrame->data, 3, width, height, frame_nv12_buff);
frame_nv12->pts = frame_nv12->pkt_dts = av_rescale_q_rnd(
frameCount,
mBsPushStreamer->mVideoCodecCtx->time_base,
mBsPushStreamer->mVideoStream->time_base,
(AVRounding)(AV_ROUND_NEAR_INF | AV_ROUND_PASS_MINMAX));
frame_nv12->pkt_duration = av_rescale_q_rnd(
1,
mBsPushStreamer->mVideoCodecCtx->time_base,
mBsPushStreamer->mVideoStream->time_base,
(AVRounding)(AV_ROUND_NEAR_INF | AV_ROUND_PASS_MINMAX));
frame_nv12->pkt_pos = -1;
hw_frame->pts = hw_frame->pkt_dts = av_rescale_q_rnd(
frameCount,
mBsPushStreamer->mVideoCodecCtx->time_base,
mBsPushStreamer->mVideoStream->time_base,
(AVRounding)(AV_ROUND_NEAR_INF | AV_ROUND_PASS_MINMAX));
hw_frame->pkt_duration = av_rescale_q_rnd(
1,
mBsPushStreamer->mVideoCodecCtx->time_base,
mBsPushStreamer->mVideoStream->time_base,
(AVRounding)(AV_ROUND_NEAR_INF | AV_ROUND_PASS_MINMAX));
hw_frame->pkt_pos = -1;
if (av_hwframe_transfer_data(hw_frame, frame_nv12, 0) < 0)
{
std::cout << "Error while transferring frame data to surface.\n";
}
t1 = getCurTime();
ret = avcodec_send_frame(mBsPushStreamer->mVideoCodecCtx, hw_frame);
if (ret >= 0)
{
ret = avcodec_receive_packet(mBsPushStreamer->mVideoCodecCtx, pkt);
if (ret >= 0)
{
t2 = getCurTime();
encodeSuccessCount++;
// 如果实际推流的是flv文件不会执行里面的fix_packet_pts
if (pkt->pts == AV_NOPTS_VALUE)
{
std::cout << "pkt->pts == AV_NOPTS_VALUE\n";
}
pkt->stream_index = mBsPushStreamer->mVideoIndex;
pkt->pos = -1;
pkt->duration = frame_nv12->pkt_duration;
ret = mBsPushStreamer->writePkt(pkt);
if (ret < 0)
{
// std::cout << fmt::format("writePkt : ret = {}\n", ret);
}
}
else
{
// std::cout << fmt::format("avcodec_receive_packet error : ret = {}\n", ret);
}
}
else
{
// std::cout << fmt::format("avcodec_send_frame error : ret = {}\n", ret);
}
frameCount++;
}
else
{
std::this_thread::sleep_for(std::chrono::milliseconds(5));
}
}
// std::cout << fmt::format("push_running is false!\n");
// std::cout << fmt::format("end stream!\n");
// av_write_trailer(mFmtCtx); //写文件尾
av_packet_unref(pkt);
pkt = NULL;
av_free(frame_nv12_buff);
frame_nv12_buff = NULL;
av_frame_free(&frame_nv12);
av_frame_unref(hw_frame);
frame_nv12 = NULL;
hw_frame = NULL;
}
int BsPushStreamer::writePkt(AVPacket *pkt)
{
mWritePkt_mtx.lock();
int ret = av_write_frame(mFmtCtx, pkt);
mWritePkt_mtx.unlock();
return ret;
}
bool BsPushStreamer::getVideoFrame(VideoFrame *&frame, int &frameQSize)
{
mRGB_VideoFrameQ_mtx.lock();
if (!mRGB_VideoFrameQ.empty())
{
frame = mRGB_VideoFrameQ.front();
mRGB_VideoFrameQ.pop();
frameQSize = mRGB_VideoFrameQ.size();
mRGB_VideoFrameQ_mtx.unlock();
return true;
}
else
{
frameQSize = 0;
mRGB_VideoFrameQ_mtx.unlock();
return false;
}
}
// void BsPushStreamer::pushVideoFrame(unsigned char *data, int width,int height)
void BsPushStreamer::stream(cv::Mat &image)
{
int size = image.cols * image.rows * image.channels();
//VideoFrame *frame = new VideoFrame(VideoFrame::BGR, image.cols, image.rows);
cv::Mat bgr = cv::Mat::zeros(image.size(), CV_8UC3);
cv::cvtColor(image, bgr, cv::COLOR_BGR2RGB);
memcpy(mVideoFrame->data, bgr.data, size);
mRGB_VideoFrameQ_mtx.lock();
nd_push_frame = true;
// mRGB_VideoFrameQ.push(frame);
mRGB_VideoFrameQ_mtx.unlock();
}
bool BsPushStreamer::videoFrameQisEmpty()
{
return mRGB_VideoFrameQ.empty();
}
unsigned char BsPushStreamer::clipValue(unsigned char x, unsigned char min_val, unsigned char max_val)
{
if (x > max_val)
{
return max_val;
}
else if (x < min_val)
{
return min_val;
}
else
{
return x;
}
}
bool BsPushStreamer::bgr24ToYuv420p(unsigned char *bgrBuf, int w, int h, unsigned char *yuvBuf)
{
unsigned char *ptrY, *ptrU, *ptrV, *ptrRGB;
memset(yuvBuf, 0, w * h * 3 / 2);
ptrY = yuvBuf;
ptrU = yuvBuf + w * h;
ptrV = ptrU + (w * h * 1 / 4);
unsigned char y, u, v, r, g, b;
for (int j = 0; j < h; ++j)
{
ptrRGB = bgrBuf + w * j * 3;
for (int i = 0; i < w; i++)
{
b = *(ptrRGB++);
g = *(ptrRGB++);
r = *(ptrRGB++);
y = (unsigned char)((66 * r + 129 * g + 25 * b + 128) >> 8) + 16;
u = (unsigned char)((-38 * r - 74 * g + 112 * b + 128) >> 8) + 128;
v = (unsigned char)((112 * r - 94 * g - 18 * b + 128) >> 8) + 128;
*(ptrY++) = clipValue(y, 0, 255);
if (j % 2 == 0 && i % 2 == 0)
{
*(ptrU++) = clipValue(u, 0, 255);
}
else
{
if (i % 2 == 0)
{
*(ptrV++) = clipValue(v, 0, 255);
}
}
}
}
return true;
}
// https://software.intel.com/en-us/node/503873
// YCbCr Color Model:
// The YCbCr color space is used for component digital video and was developed as part of the ITU-R BT.601 Recommendation. YCbCr is a scaled and offset version of the YUV color space.
// The Intel IPP functions use the following basic equations [Jack01] to convert between R'G'B' in the range 0-255 and Y'Cb'Cr' (this notation means that all components are derived from gamma-corrected R'G'B'):
// Y' = 0.257*R' + 0.504*G' + 0.098*B' + 16
// Cb' = -0.148*R' - 0.291*G' + 0.439*B' + 128
// Cr' = 0.439*R' - 0.368*G' - 0.071*B' + 128
// Y' = 0.257*R' + 0.504*G' + 0.098*B' + 16
static float Rgb2Y(float r0, float g0, float b0)
{
float y0 = 0.257f * r0 + 0.504f * g0 + 0.098f * b0 + 16.0f;
return y0;
}
// U equals Cb'
// Cb' = -0.148*R' - 0.291*G' + 0.439*B' + 128
static float Rgb2U(float r0, float g0, float b0)
{
float u0 = -0.148f * r0 - 0.291f * g0 + 0.439f * b0 + 128.0f;
return u0;
}
// V equals Cr'
// Cr' = 0.439*R' - 0.368*G' - 0.071*B' + 128
static float Rgb2V(float r0, float g0, float b0)
{
float v0 = 0.439f * r0 - 0.368f * g0 - 0.071f * b0 + 128.0f;
return v0;
}
// Convert two rows from RGB to two Y rows, and one row of interleaved U,V.
// I0 and I1 points two sequential source rows.
// I0 -> rgbrgbrgbrgbrgbrgb...
// I1 -> rgbrgbrgbrgbrgbrgb...
// Y0 and Y1 points two sequential destination rows of Y plane.
// Y0 -> yyyyyy
// Y1 -> yyyyyy
// UV0 points destination rows of interleaved UV plane.
// UV0 -> uvuvuv
static void Rgb2NV12TwoRows(const unsigned char I0[],
const unsigned char I1[],
int step,
const int image_width,
unsigned char Y0[],
unsigned char Y1[],
unsigned char UV0[])
{
int x; // Column index
// Process 4 source pixels per iteration (2 pixels of row I0 and 2 pixels of row I1).
for (x = 0; x < image_width; x += 2)
{
// Load R,G,B elements from first row (and convert to float).
float r00 = (float)I0[x * step + 0];
float g00 = (float)I0[x * step + 1];
float b00 = (float)I0[x * step + 2];
// Load next R,G,B elements from first row (and convert to float).
float r01 = (float)I0[x * step + step + 0];
float g01 = (float)I0[x * step + step + 1];
float b01 = (float)I0[x * step + step + 2];
// Load R,G,B elements from second row (and convert to float).
float r10 = (float)I1[x * step + 0];
float g10 = (float)I1[x * step + 1];
float b10 = (float)I1[x * step + 2];
// Load next R,G,B elements from second row (and convert to float).
float r11 = (float)I1[x * step + step + 0];
float g11 = (float)I1[x * step + step + 1];
float b11 = (float)I1[x * step + step + 2];
// Calculate 4 Y elements.
float y00 = Rgb2Y(r00, g00, b00);
float y01 = Rgb2Y(r01, g01, b01);
float y10 = Rgb2Y(r10, g10, b10);
float y11 = Rgb2Y(r11, g11, b11);
// Calculate 4 U elements.
float u00 = Rgb2U(r00, g00, b00);
float u01 = Rgb2U(r01, g01, b01);
float u10 = Rgb2U(r10, g10, b10);
float u11 = Rgb2U(r11, g11, b11);
// Calculate 4 V elements.
float v00 = Rgb2V(r00, g00, b00);
float v01 = Rgb2V(r01, g01, b01);
float v10 = Rgb2V(r10, g10, b10);
float v11 = Rgb2V(r11, g11, b11);
// Calculate destination U element: average of 2x2 "original" U elements.
float u0 = (u00 + u01 + u10 + u11) * 0.25f;
// Calculate destination V element: average of 2x2 "original" V elements.
float v0 = (v00 + v01 + v10 + v11) * 0.25f;
// Store 4 Y elements (two in first row and two in second row).
Y0[x + 0] = (unsigned char)(y00 + 0.5f);
Y0[x + 1] = (unsigned char)(y01 + 0.5f);
Y1[x + 0] = (unsigned char)(y10 + 0.5f);
Y1[x + 1] = (unsigned char)(y11 + 0.5f);
// Store destination U element.
UV0[x + 0] = (unsigned char)(u0 + 0.5f);
// Store destination V element (next to stored U element).
UV0[x + 1] = (unsigned char)(v0 + 0.5f);
}
}
// Convert image I from pixel ordered RGB to NV12 format.
// I - Input image in pixel ordered RGB format
// image_width - Number of columns of I
// image_height - Number of rows of I
// J - Destination "image" in NV12 format.
// I is pixel ordered RGB color format (size in bytes is image_width*image_height*3):
// RGBRGBRGBRGBRGBRGB
// RGBRGBRGBRGBRGBRGB
// RGBRGBRGBRGBRGBRGB
// RGBRGBRGBRGBRGBRGB
//
// J is in NV12 format (size in bytes is image_width*image_height*3/2):
// YYYYYY
// YYYYYY
// UVUVUV
// Each element of destination U is average of 2x2 "original" U elements
// Each element of destination V is average of 2x2 "original" V elements
//
// Limitations:
// 1. image_width must be a multiple of 2.
// 2. image_height must be a multiple of 2.
// 3. I and J must be two separate arrays (in place computation is not supported).
void BsPushStreamer::Rgb2NV12(const unsigned char I[], int step,
const int image_width,
const int image_height,
unsigned char J[])
{
// In NV12 format, UV plane starts below Y plane.
unsigned char *UV = &J[image_width * image_height];
// I0 and I1 points two sequential source rows.
const unsigned char *I0; // I0 -> rgbrgbrgbrgbrgbrgb...
const unsigned char *I1; // I1 -> rgbrgbrgbrgbrgbrgb...
// Y0 and Y1 points two sequential destination rows of Y plane.
unsigned char *Y0; // Y0 -> yyyyyy
unsigned char *Y1; // Y1 -> yyyyyy
// UV0 points destination rows of interleaved UV plane.
unsigned char *UV0; // UV0 -> uvuvuv
int y; // Row index
// In each iteration: process two rows of Y plane, and one row of interleaved UV plane.
for (y = 0; y < image_height; y += 2)
{
I0 = &I[y * image_width * step]; // Input row width is image_width*3 bytes (each pixel is R,G,B).
I1 = &I[(y + 1) * image_width * step];
Y0 = &J[y * image_width]; // Output Y row width is image_width bytes (one Y element per pixel).
Y1 = &J[(y + 1) * image_width];
UV0 = &UV[(y / 2) * image_width]; // Output UV row - width is same as Y row width.
// Process two source rows into: Two Y destination row, and one destination interleaved U,V row.
Rgb2NV12TwoRows(I0,
I1,
step,
image_width,
Y0,
Y1,
UV0);
}
}

View File

@@ -0,0 +1,88 @@
#pragma once
#include <iostream>
#include <thread>
#include <chrono>
// #include <fmt/core.h>
// #include <glog/logging.h>
#include <queue>
#include <mutex>
extern "C"
{
#include <libavcodec/avcodec.h>
#include <libavformat/avformat.h>
#include <libswscale/swscale.h>
#include <libavutil/imgutils.h>
// #include <libavutil/error.h>
#include <libswresample/swresample.h>
#include <libavutil/pixdesc.h>
#include <libavutil/hwcontext.h>
}
#include <opencv2/core/core.hpp>
#include <opencv2/opencv.hpp>
#include "bs_common.h"
using namespace cv;
class BsPushStreamer
{
public:
BsPushStreamer();
~BsPushStreamer();
// 用于初始化视频推流,仅调用一次
bool setup(std::string name, int width, int height, int fps, std::string encoder, int bitrate);
// 推流一帧图像,在循环中被调用
void stream(cv::Mat &image);
// 连接流媒体服务器
bool connect(std::string name, int width, int height, int fps, std::string encoder, int bitrate);
void start();
void stop() { push_running = false; };
// 编码视频帧并推流
static void encodeVideoAndWriteStreamThread(void *arg);
bool videoFrameQisEmpty();
int writePkt(AVPacket *pkt);
// 上下文
AVFormatContext *mFmtCtx = nullptr;
// 视频帧
AVCodecContext *mVideoCodecCtx = NULL;
AVStream *mVideoStream = NULL;
VideoFrame *mVideoFrame = NULL;
AVBufferRef *hw_device_ctx = NULL;
int err;
int mVideoIndex = -1;
// YAML::Node yaml_cfg;
private:
// 从mRGB_VideoFrameQ里面获取RGBframe
bool getVideoFrame(VideoFrame *&frame, int &frameQSize);
// bgr24转yuv420p
unsigned char clipValue(unsigned char x, unsigned char min_val, unsigned char max_val);
bool bgr24ToYuv420p(unsigned char *bgrBuf, int w, int h, unsigned char *yuvBuf);
void Rgb2NV12(const unsigned char I[], int step, const int image_width, const int image_height, unsigned char J[]);
bool push_running = false;
bool nd_push_frame = false;
// 视频帧
std::queue<VideoFrame *> mRGB_VideoFrameQ;
std::mutex mRGB_VideoFrameQ_mtx;
// 推流锁
std::mutex mWritePkt_mtx;
std::thread *mThread;
};

View File

@@ -0,0 +1,655 @@
#include "bs_video_saver.h"
/*
amov_rtsp
53248e16cc899903cf296df468977c60d7d73aa7
*/
BsVideoSaver::BsVideoSaver()
{
}
BsVideoSaver::~BsVideoSaver()
{
}
static int set_hwframe_ctx(AVCodecContext *ctx, AVBufferRef *hw_device_ctx, int width, int height)
{
AVBufferRef *hw_frames_ref;
AVHWFramesContext *frames_ctx = NULL;
int err = 0;
if (!(hw_frames_ref = av_hwframe_ctx_alloc(hw_device_ctx)))
{
fprintf(stderr, "Failed to create VAAPI frame context.\n");
return -1;
}
frames_ctx = (AVHWFramesContext *)(hw_frames_ref->data);
frames_ctx->format = AV_PIX_FMT_VAAPI;
frames_ctx->sw_format = AV_PIX_FMT_NV12;
frames_ctx->width = width;
frames_ctx->height = height;
frames_ctx->initial_pool_size = 20;
if ((err = av_hwframe_ctx_init(hw_frames_ref)) < 0)
{
// fprintf(stderr, "Failed to initialize VAAPI frame context."
// "Error code: %s\n",av_err2str(err));
av_buffer_unref(&hw_frames_ref);
return err;
}
ctx->hw_frames_ctx = av_buffer_ref(hw_frames_ref);
if (!ctx->hw_frames_ctx)
err = AVERROR(ENOMEM);
av_buffer_unref(&hw_frames_ref);
return err;
}
bool BsVideoSaver::setup(std::string name, int width, int height, int fps, std::string encoder, int bitrate = 4)
{
// 重置状态然后初始化
this->width = width;
this->height = height;
// 线程停止
if (mThread != nullptr)
{
this->stop();
}
// 编码器重置
if (mVideoCodecCtx != NULL)
{
avcodec_free_context(&mVideoCodecCtx);
}
if (!this->init(name, width, height, fps, encoder, bitrate))
{
std::cout << "BsVideoSaver::setup error\n";
return false;
}
std::cout << "BsStreamer::setup Success!\n";
start();
return true;
}
void BsVideoSaver::start()
{
mThread = new std::thread(BsVideoSaver::encodeVideoAndSaveThread, this);
mThread->native_handle();
push_running = true;
}
void BsVideoSaver::stop()
{
if (mThread != nullptr)
{
push_running = false;
mThread->join();
mThread = nullptr;
}
}
bool BsVideoSaver::init(std::string name, int width, int height, int fps, std::string encoder, int bitrate)
{
// 初始化上下文
if (avformat_alloc_output_context2(&mFmtCtx, NULL, NULL, name.c_str()) < 0)
{
std::cout << "avformat_alloc_output_context2 error\n";
return false;
}
// 初始化视频编码器
// AVCodec *videoCodec = avcodec_find_encoder(AV_CODEC_ID_H264);
// AVCodec *videoCodec = avcodec_find_encoder_by_name("h264_nvenc");
err = av_hwdevice_ctx_create(&hw_device_ctx, AV_HWDEVICE_TYPE_VAAPI,
NULL, NULL, 0);
AVCodec *videoCodec = avcodec_find_encoder_by_name(encoder.c_str());
if (!videoCodec)
{
// std::cout << fmt::format("Using encoder:[{}] error!\n", encoder);
videoCodec = avcodec_find_encoder(AV_CODEC_ID_H264);
if (!videoCodec)
{
std::cout << "avcodec_alloc_context3 error";
return false;
}
std::cout << "Using default H264 encoder!\n";
}
mVideoCodecCtx = avcodec_alloc_context3(videoCodec);
if (!mVideoCodecCtx)
{
std::cout << "avcodec_alloc_context3 error";
return false;
}
// 压缩视频bit位大小 300kB
int bit_rate = bitrate * 1024 * 1024 * 8;
// CBRConstant BitRate - 固定比特率
mVideoCodecCtx->flags |= AV_CODEC_FLAG_QSCALE;
mVideoCodecCtx->bit_rate = bit_rate;
mVideoCodecCtx->rc_min_rate = bit_rate;
mVideoCodecCtx->rc_max_rate = bit_rate;
mVideoCodecCtx->bit_rate_tolerance = bit_rate;
mVideoCodecCtx->codec_id = videoCodec->id;
// 不支持AV_PIX_FMT_BGR24直接进行编码
mVideoCodecCtx->pix_fmt = AV_PIX_FMT_VAAPI;
mVideoCodecCtx->codec_type = AVMEDIA_TYPE_VIDEO;
mVideoCodecCtx->width = width;
mVideoCodecCtx->height = height;
mVideoCodecCtx->time_base = {1, fps};
mVideoCodecCtx->framerate = {fps, 1};
mVideoCodecCtx->gop_size = 12;
mVideoCodecCtx->max_b_frames = 0;
mVideoCodecCtx->thread_count = 1;
// mVideoCodecCtx->sample_aspect_ratio = (AVRational){1, 1};
AVDictionary *video_codec_options = NULL;
av_dict_set(&video_codec_options, "profile", "main", 0);
// av_dict_set(&video_codec_options, "preset", "superfast", 0);
av_dict_set(&video_codec_options, "tune", "fastdecode", 0);
if ((err = set_hwframe_ctx(mVideoCodecCtx, hw_device_ctx, width, height)) < 0)
{
std::cout << "set_hwframe_ctx error\n";
return false;
}
if (avcodec_open2(mVideoCodecCtx, videoCodec, &video_codec_options) < 0)
{
std::cout << "avcodec_open2 error\n";
return false;
}
mVideoStream = avformat_new_stream(mFmtCtx, videoCodec);
if (!mVideoStream)
{
std::cout << "avformat_new_stream error\n";
return false;
}
mVideoStream->id = mFmtCtx->nb_streams - 1;
// stream的time_base参数非常重要它表示将现实中的一秒钟分为多少个时间基, 在下面调用avformat_write_header时自动完成
avcodec_parameters_from_context(mVideoStream->codecpar, mVideoCodecCtx);
mVideoIndex = mVideoStream->id;
// open output url
av_dump_format(mFmtCtx, 0, name.c_str(), 1);
if (!(mFmtCtx->oformat->flags & AVFMT_NOFILE))
{
int ret = avio_open(&mFmtCtx->pb, name.c_str(), AVIO_FLAG_WRITE);
if (ret < 0)
{
// std::cout << fmt::format("avio_open error url: {}\n", name.c_str());
// std::cout << fmt::format("ret = {} : {}\n", ret, av_err2str(ret));
// std::cout << fmt::format("ret = {}\n", ret);
return false;
}
}
AVDictionary *fmt_options = NULL;
av_dict_set(&fmt_options, "bufsize", "1024", 0);
mFmtCtx->video_codec_id = mFmtCtx->oformat->video_codec;
mFmtCtx->audio_codec_id = mFmtCtx->oformat->audio_codec;
// 调用该函数会将所有stream的time_base自动设置一个值通常是1/90000或1/1000这表示一秒钟表示的时间基长度
if (avformat_write_header(mFmtCtx, &fmt_options) < 0)
{
std::cout << "avformat_write_header error\n";
return false;
}
return true;
}
void BsVideoSaver::encodeVideoAndSaveThread(void *arg)
{
// PushExecutor *executor = (PushExecutor *)arg;
BsVideoSaver *mBsVideoSaver = (BsVideoSaver *)arg;
int width = mBsVideoSaver->width;
int height = mBsVideoSaver->height;
// 未编码的视频帧bgr格式
VideoFrame *videoFrame = NULL;
// 未编码视频帧队列当前长度
int videoFrameQSize = 0;
AVFrame *hw_frame = NULL;
AVFrame *frame_nv12 = av_frame_alloc();
frame_nv12->format = AV_PIX_FMT_NV12;
frame_nv12->width = width;
frame_nv12->height = height;
int frame_nv12_buff_size = av_image_get_buffer_size(AV_PIX_FMT_NV12, width, height, 1);
uint8_t *frame_nv12_buff = (uint8_t *)av_malloc(frame_nv12_buff_size);
av_image_fill_arrays(
frame_nv12->data, frame_nv12->linesize,
frame_nv12_buff,
AV_PIX_FMT_NV12,
width, height, 1);
/* read data into software frame, and transfer them into hw frame */
// sw_frame->width = width;
// sw_frame->height = height;
// sw_frame->format = AV_PIX_FMT_NV12;
if (!(hw_frame = av_frame_alloc()))
{
std::cout << "Error while av_frame_alloc().\n";
}
if (av_hwframe_get_buffer(mBsVideoSaver->mVideoCodecCtx->hw_frames_ctx, hw_frame, 0) < 0)
{
std::cout << "Error while av_hwframe_get_buffer.\n";
}
if (!hw_frame->hw_frames_ctx)
{
std::cout << "Error while hw_frames_ctx.\n";
}
// 编码后的视频帧
AVPacket *pkt = av_packet_alloc();
int64_t encodeSuccessCount = 0;
int64_t frameCount = 0;
int64_t t1 = 0;
int64_t t2 = 0;
int ret = -1;
while (mBsVideoSaver->push_running)
{
if (mBsVideoSaver->getVideoFrame(videoFrame, videoFrameQSize))
{
// frame_bgr 转 frame_nv12
//mBsVideoSaver->bgr24ToYuv420p(videoFrame->data, width, height, frame_nv12_buff);
mBsVideoSaver->Rgb2NV12(videoFrame->data, 3, width, height, frame_nv12_buff);
// RGB2YUV_NV12(videoFrame->data, frame_nv12_buff, width, height );
frame_nv12->pts = frame_nv12->pkt_dts = av_rescale_q_rnd(
frameCount,
mBsVideoSaver->mVideoCodecCtx->time_base,
mBsVideoSaver->mVideoStream->time_base,
(AVRounding)(AV_ROUND_NEAR_INF | AV_ROUND_PASS_MINMAX));
frame_nv12->pkt_duration = av_rescale_q_rnd(
1,
mBsVideoSaver->mVideoCodecCtx->time_base,
mBsVideoSaver->mVideoStream->time_base,
(AVRounding)(AV_ROUND_NEAR_INF | AV_ROUND_PASS_MINMAX));
frame_nv12->pkt_pos = frameCount;
hw_frame->pts = hw_frame->pkt_dts = av_rescale_q_rnd(
frameCount,
mBsVideoSaver->mVideoCodecCtx->time_base,
mBsVideoSaver->mVideoStream->time_base,
(AVRounding)(AV_ROUND_NEAR_INF | AV_ROUND_PASS_MINMAX));
hw_frame->pkt_duration = av_rescale_q_rnd(
1,
mBsVideoSaver->mVideoCodecCtx->time_base,
mBsVideoSaver->mVideoStream->time_base,
(AVRounding)(AV_ROUND_NEAR_INF | AV_ROUND_PASS_MINMAX));
hw_frame->pkt_pos = frameCount;
if (av_hwframe_transfer_data(hw_frame, frame_nv12, 0) < 0)
{
std::cout << "Error while transferring frame data to surface.\n";
}
t1 = getCurTime();
ret = avcodec_send_frame(mBsVideoSaver->mVideoCodecCtx, hw_frame);
if (ret >= 0)
{
ret = avcodec_receive_packet(mBsVideoSaver->mVideoCodecCtx, pkt);
if (ret >= 0)
{
t2 = getCurTime();
encodeSuccessCount++;
pkt->stream_index = mBsVideoSaver->mVideoIndex;
pkt->pos = frameCount;
pkt->duration = frame_nv12->pkt_duration;
ret = mBsVideoSaver->writePkt(pkt);
if (ret < 0)
{
// std::cout << fmt::format("writePkt : ret = {}\n", ret);
}
}
else
{
// std::cout << fmt::format("avcodec_receive_packet error : ret = {}\n", ret);
}
}
else
{
// std::cout << fmt::format("avcodec_send_frame error : ret = {}\n", ret);
}
frameCount++;
// 释放资源
delete videoFrame;
videoFrame = NULL;
}
else
{
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
}
// std::cout << fmt::format("push_running is false!\n");
// std::cout << fmt::format("end stream!\n");
// 写文件尾
av_write_trailer(mBsVideoSaver->mFmtCtx);
av_packet_unref(pkt);
pkt = NULL;
av_free(frame_nv12_buff);
frame_nv12_buff = NULL;
av_frame_free(&frame_nv12);
av_frame_free(&hw_frame);
// av_frame_unref(frame_nv12);
frame_nv12 = NULL;
}
int BsVideoSaver::writePkt(AVPacket *pkt)
{
mWritePkt_mtx.lock();
int ret = av_write_frame(mFmtCtx, pkt);
mWritePkt_mtx.unlock();
return ret;
}
bool BsVideoSaver::getVideoFrame(VideoFrame *&frame, int &frameQSize)
{
mRGB_VideoFrameQ_mtx.lock();
if (!mRGB_VideoFrameQ.empty())
{
frame = mRGB_VideoFrameQ.front();
mRGB_VideoFrameQ.pop();
frameQSize = mRGB_VideoFrameQ.size();
mRGB_VideoFrameQ_mtx.unlock();
return true;
}
else
{
frameQSize = 0;
mRGB_VideoFrameQ_mtx.unlock();
return false;
}
}
void BsVideoSaver::write(cv::Mat &image)
{
int size = image.cols * image.rows * image.channels();
VideoFrame *frame = new VideoFrame(VideoFrame::BGR, image.cols, image.rows);
cv::Mat bgr = cv::Mat::zeros(image.size(), CV_8UC3);
cv::cvtColor(image, bgr, cv::COLOR_BGR2RGB);
memcpy(frame->data, bgr.data, size);
mRGB_VideoFrameQ_mtx.lock();
mRGB_VideoFrameQ.push(frame);
mRGB_VideoFrameQ_mtx.unlock();
}
bool BsVideoSaver::videoFrameQisEmpty()
{
return mRGB_VideoFrameQ.empty();
}
unsigned char BsVideoSaver::clipValue(unsigned char x, unsigned char min_val, unsigned char max_val)
{
if (x > max_val)
{
return max_val;
}
else if (x < min_val)
{
return min_val;
}
else
{
return x;
}
}
bool BsVideoSaver::bgr24ToYuv420p(unsigned char *bgrBuf, int w, int h, unsigned char *yuvBuf)
{
unsigned char *ptrY, *ptrU, *ptrV, *ptrRGB;
memset(yuvBuf, 0, w * h * 3 / 2);
ptrY = yuvBuf;
ptrU = yuvBuf + w * h;
ptrV = ptrU + (w * h * 1 / 4);
unsigned char y, u, v, r, g, b;
for (int j = 0; j < h; ++j)
{
ptrRGB = bgrBuf + w * j * 3;
for (int i = 0; i < w; i++)
{
b = *(ptrRGB++);
g = *(ptrRGB++);
r = *(ptrRGB++);
y = (unsigned char)((66 * r + 129 * g + 25 * b + 128) >> 8) + 16;
u = (unsigned char)((-38 * r - 74 * g + 112 * b + 128) >> 8) + 128;
v = (unsigned char)((112 * r - 94 * g - 18 * b + 128) >> 8) + 128;
*(ptrY++) = clipValue(y, 0, 255);
if (j % 2 == 0 && i % 2 == 0)
{
*(ptrU++) = clipValue(u, 0, 255);
}
else
{
if (i % 2 == 0)
{
*(ptrV++) = clipValue(v, 0, 255);
}
}
}
}
return true;
}
//https://software.intel.com/en-us/node/503873
//YCbCr Color Model:
// The YCbCr color space is used for component digital video and was developed as part of the ITU-R BT.601 Recommendation. YCbCr is a scaled and offset version of the YUV color space.
// The Intel IPP functions use the following basic equations [Jack01] to convert between R'G'B' in the range 0-255 and Y'Cb'Cr' (this notation means that all components are derived from gamma-corrected R'G'B'):
// Y' = 0.257*R' + 0.504*G' + 0.098*B' + 16
// Cb' = -0.148*R' - 0.291*G' + 0.439*B' + 128
// Cr' = 0.439*R' - 0.368*G' - 0.071*B' + 128
//Y' = 0.257*R' + 0.504*G' + 0.098*B' + 16
static float Rgb2Y(float r0, float g0, float b0)
{
float y0 = 0.257f*r0 + 0.504f*g0 + 0.098f*b0 + 16.0f;
return y0;
}
//U equals Cb'
//Cb' = -0.148*R' - 0.291*G' + 0.439*B' + 128
static float Rgb2U(float r0, float g0, float b0)
{
float u0 = -0.148f*r0 - 0.291f*g0 + 0.439f*b0 + 128.0f;
return u0;
}
//V equals Cr'
//Cr' = 0.439*R' - 0.368*G' - 0.071*B' + 128
static float Rgb2V(float r0, float g0, float b0)
{
float v0 = 0.439f*r0 - 0.368f*g0 - 0.071f*b0 + 128.0f;
return v0;
}
//Convert two rows from RGB to two Y rows, and one row of interleaved U,V.
//I0 and I1 points two sequential source rows.
//I0 -> rgbrgbrgbrgbrgbrgb...
//I1 -> rgbrgbrgbrgbrgbrgb...
//Y0 and Y1 points two sequential destination rows of Y plane.
//Y0 -> yyyyyy
//Y1 -> yyyyyy
//UV0 points destination rows of interleaved UV plane.
//UV0 -> uvuvuv
static void Rgb2NV12TwoRows(const unsigned char I0[],
const unsigned char I1[],
int step,
const int image_width,
unsigned char Y0[],
unsigned char Y1[],
unsigned char UV0[])
{
int x; //Column index
//Process 4 source pixels per iteration (2 pixels of row I0 and 2 pixels of row I1).
for (x = 0; x < image_width; x += 2)
{
//Load R,G,B elements from first row (and convert to float).
float r00 = (float)I0[x*step + 0];
float g00 = (float)I0[x*step + 1];
float b00 = (float)I0[x*step + 2];
//Load next R,G,B elements from first row (and convert to float).
float r01 = (float)I0[x*step + step+0];
float g01 = (float)I0[x*step + step+1];
float b01 = (float)I0[x*step + step+2];
//Load R,G,B elements from second row (and convert to float).
float r10 = (float)I1[x*step + 0];
float g10 = (float)I1[x*step + 1];
float b10 = (float)I1[x*step + 2];
//Load next R,G,B elements from second row (and convert to float).
float r11 = (float)I1[x*step + step+0];
float g11 = (float)I1[x*step + step+1];
float b11 = (float)I1[x*step + step+2];
//Calculate 4 Y elements.
float y00 = Rgb2Y(r00, g00, b00);
float y01 = Rgb2Y(r01, g01, b01);
float y10 = Rgb2Y(r10, g10, b10);
float y11 = Rgb2Y(r11, g11, b11);
//Calculate 4 U elements.
float u00 = Rgb2U(r00, g00, b00);
float u01 = Rgb2U(r01, g01, b01);
float u10 = Rgb2U(r10, g10, b10);
float u11 = Rgb2U(r11, g11, b11);
//Calculate 4 V elements.
float v00 = Rgb2V(r00, g00, b00);
float v01 = Rgb2V(r01, g01, b01);
float v10 = Rgb2V(r10, g10, b10);
float v11 = Rgb2V(r11, g11, b11);
//Calculate destination U element: average of 2x2 "original" U elements.
float u0 = (u00 + u01 + u10 + u11)*0.25f;
//Calculate destination V element: average of 2x2 "original" V elements.
float v0 = (v00 + v01 + v10 + v11)*0.25f;
//Store 4 Y elements (two in first row and two in second row).
Y0[x + 0] = (unsigned char)(y00 + 0.5f);
Y0[x + 1] = (unsigned char)(y01 + 0.5f);
Y1[x + 0] = (unsigned char)(y10 + 0.5f);
Y1[x + 1] = (unsigned char)(y11 + 0.5f);
//Store destination U element.
UV0[x + 0] = (unsigned char)(u0 + 0.5f);
//Store destination V element (next to stored U element).
UV0[x + 1] = (unsigned char)(v0 + 0.5f);
}
}
//Convert image I from pixel ordered RGB to NV12 format.
//I - Input image in pixel ordered RGB format
//image_width - Number of columns of I
//image_height - Number of rows of I
//J - Destination "image" in NV12 format.
//I is pixel ordered RGB color format (size in bytes is image_width*image_height*3):
//RGBRGBRGBRGBRGBRGB
//RGBRGBRGBRGBRGBRGB
//RGBRGBRGBRGBRGBRGB
//RGBRGBRGBRGBRGBRGB
//
//J is in NV12 format (size in bytes is image_width*image_height*3/2):
//YYYYYY
//YYYYYY
//UVUVUV
//Each element of destination U is average of 2x2 "original" U elements
//Each element of destination V is average of 2x2 "original" V elements
//
//Limitations:
//1. image_width must be a multiple of 2.
//2. image_height must be a multiple of 2.
//3. I and J must be two separate arrays (in place computation is not supported).
void BsVideoSaver::Rgb2NV12(const unsigned char I[], int step,
const int image_width,
const int image_height,
unsigned char J[])
{
//In NV12 format, UV plane starts below Y plane.
unsigned char *UV = &J[image_width*image_height];
//I0 and I1 points two sequential source rows.
const unsigned char *I0; //I0 -> rgbrgbrgbrgbrgbrgb...
const unsigned char *I1; //I1 -> rgbrgbrgbrgbrgbrgb...
//Y0 and Y1 points two sequential destination rows of Y plane.
unsigned char *Y0; //Y0 -> yyyyyy
unsigned char *Y1; //Y1 -> yyyyyy
//UV0 points destination rows of interleaved UV plane.
unsigned char *UV0; //UV0 -> uvuvuv
int y; //Row index
//In each iteration: process two rows of Y plane, and one row of interleaved UV plane.
for (y = 0; y < image_height; y += 2)
{
I0 = &I[y*image_width*step]; //Input row width is image_width*3 bytes (each pixel is R,G,B).
I1 = &I[(y+1)*image_width*step];
Y0 = &J[y*image_width]; //Output Y row width is image_width bytes (one Y element per pixel).
Y1 = &J[(y+1)*image_width];
UV0 = &UV[(y/2)*image_width]; //Output UV row - width is same as Y row width.
//Process two source rows into: Two Y destination row, and one destination interleaved U,V row.
Rgb2NV12TwoRows(I0,
I1,
step,
image_width,
Y0,
Y1,
UV0);
}
}

View File

@@ -0,0 +1,101 @@
#pragma once
#include <iostream>
#include <thread>
#include <chrono>
#include <fmt/core.h>
// #include <glog/logging.h>
#include <queue>
#include <mutex>
extern "C"
{
#include <libavcodec/avcodec.h>
#include <libavformat/avformat.h>
#include <libswscale/swscale.h>
#include <libavutil/imgutils.h>
// #include <libavutil/error.h>
#include <libswresample/swresample.h>
#include <libavutil/pixdesc.h>
#include <libavutil/hwcontext.h>
}
#include <opencv2/core/core.hpp>
#include <opencv2/opencv.hpp>
#include "bs_common.h"
using namespace cv;
class BsVideoSaver
{
public:
BsVideoSaver();
~BsVideoSaver();
// 用于初始化视频推流,仅调用一次
bool setup(std::string name, int width, int height, int fps, std::string encoder, int bitrate);
// 推流一帧图像,在循环中被调用
void write(cv::Mat& image);
// 连接流媒体服务器
bool init(std::string name, int width, int height, int fps, std::string encoder, int bitrate);
void start();
void stop();
// 编码视频帧并推流
static void encodeVideoAndSaveThread(void* arg);
bool videoFrameQisEmpty();
int writePkt(AVPacket *pkt);
// 上下文
AVFormatContext *mFmtCtx = nullptr;
// 视频帧
AVCodecContext *mVideoCodecCtx = NULL;
AVStream *mVideoStream = NULL;
AVBufferRef *hw_device_ctx = NULL;
int err;
int mVideoIndex = -1;
private:
// 从mRGB_VideoFrameQ里面获取RGBframe
bool getVideoFrame(VideoFrame *&frame, int &frameQSize);
// bgr24转yuv420p
unsigned char clipValue(unsigned char x, unsigned char min_val, unsigned char max_val);
bool bgr24ToYuv420p(unsigned char *bgrBuf, int w, int h, unsigned char *yuvBuf);
void Rgb2NV12(const unsigned char I[], int step, const int image_width, const int image_height, unsigned char J[]);
// void RGB2YUV_NV12(uint8_t* rgbBufIn, uint8_t* yuvBufOut, int nWidth, int nHeight);
int width = -1;
int height = -1;
bool push_running = false;
bool nd_push_frame = false;
// 视频帧
std::queue<VideoFrame *> mRGB_VideoFrameQ;
std::mutex mRGB_VideoFrameQ_mtx;
// 推流锁
std::mutex mWritePkt_mtx;
std::thread* mThread = nullptr;
};

View File

@@ -1059,6 +1059,7 @@ CameraBase::CameraBase(CameraType type, int id)
this->_saturation = -1;
this->_hue = -1;
this->_exposure = -1;
this->_fourcc = "MJPG";
this->open(type, id);
}
@@ -1067,6 +1068,14 @@ CameraBase::~CameraBase()
this->_is_running = false;
// this->_tt.join();
}
std::string CameraBase::getFourcc()
{
return this->_fourcc;
}
void CameraBase::setFourcc(std::string fourcc)
{
this->_fourcc = fourcc;
}
void CameraBase::setWH(int width, int height)
{
this->_width = width;
@@ -1164,6 +1173,7 @@ void CameraBase::openImpl()
}
void CameraBase::open(CameraType type, int id)
{
this->release();
this->_type = type;
this->_camera_id = id;
@@ -1185,8 +1195,11 @@ void CameraBase::_run()
{
while (this->_is_running && this->_cap.isOpened())
{
this->_cap >> this->_frame;
this->_is_updated = true;
if (this->_type != CameraType::VIDEO || this->_is_updated == false)
{
this->_cap >> this->_frame;
this->_is_updated = true;
}
std::this_thread::sleep_for(std::chrono::milliseconds(2));
}
}
@@ -1199,11 +1212,11 @@ bool CameraBase::read(cv::Mat& image)
{
if (this->_is_updated)
{
this->_is_updated = false;
this->_frame.copyTo(image);
this->_is_updated = false;
break;
}
std::this_thread::sleep_for(std::chrono::milliseconds(20));
std::this_thread::sleep_for(std::chrono::milliseconds(2));
n_try ++;
}
}
@@ -1215,7 +1228,10 @@ bool CameraBase::read(cv::Mat& image)
}
void CameraBase::release()
{
_cap.release();
this->_is_running = false;
this->_is_updated = false;
if (this->_cap.isOpened())
this->_cap.release();
}

View File

@@ -19,12 +19,16 @@ void Camera::openImpl()
if (this->_type == CameraType::V4L2CAM)
{
this->_cap.open(this->_camera_id, cv::CAP_V4L2);
// this->_cap.set(cv::CAP_PROP_FOURCC, cv::VideoWriter::fourcc('Y', 'U', 'Y', 'V'));
}
if (this->_type == CameraType::WEBCAM)
{
this->_cap.open(this->_camera_id);
}
if (_fourcc.size() >= 4)
{
const char *fourcc_cstr = _fourcc.c_str();
this->_cap.set(cv::CAP_PROP_FOURCC, cv::VideoWriter::fourcc(fourcc_cstr[0], fourcc_cstr[1], fourcc_cstr[2], fourcc_cstr[3]));
}
if (this->_width > 0 && this->_height > 0)
{
this->_cap.set(cv::CAP_PROP_FRAME_WIDTH, this->_width);
@@ -72,18 +76,20 @@ void Camera::openImpl()
this->_fps = 30;
}
#ifdef PLATFORM_JETSON
sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! \
application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! \
nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false",
this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
#else
#if defined(PLATFORM_X86_CUDA) || defined(PLATFORM_X86_INTEL)
sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! \
application/x-rtp,media=video ! rtph264depay ! parsebin ! avdec_h264 ! \
videoconvert ! appsink sync=false",
this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
#endif
printf("%s\r\n",pipe);
#ifdef PLATFORM_JETSON
sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! \
application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! \
nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false",
this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
#endif
// printf("%s\r\n",pipe);
this->_cap.open(pipe, cv::CAP_GSTREAMER);
}
else if (this->_type == CameraType::GX40)
@@ -98,7 +104,7 @@ void Camera::openImpl()
{
this->_port = 554;
}
#ifdef PLATFORM_X86_CUDA
#if defined(PLATFORM_X86_CUDA) || defined(PLATFORM_X86_INTEL)
camera_url << "rtspsrc location = rtsp://user:0000@" << this->_ip << ":" << this->_port
<< "/cam/realmonitor?channel=1&subtype=0 latency=100 ! application/x-rtp,media=video ! \
rtph265depay ! parsebin ! avdec_h265 ! videoscale ! video/x-raw,width=(int)" << this->_width
@@ -130,7 +136,10 @@ void Camera::openImpl()
this->_fps = 30;
}
sprintf(pipe, "nvarguscamerasrc sensor-id=%d ! video/x-raw(memory:NVMM), width=(int)%d, height=(int)%d, format=(string)NV12, framerate=(fraction)%d/1 ! nvvidconv flip-method=0 ! video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink", this->_camera_id, this->_width, this->_height, this->_fps, this->_width, this->_height);
sprintf(pipe, "nvarguscamerasrc sensor-id=%d ee-mode=0 tnr-mode=0 aeantibanding=0 wbmode=0 ! \
video/x-raw(memory:NVMM), width=(int)%d, height=(int)%d, format=(string)NV12, framerate=(fraction)%d/1 ! \
nvvidconv ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink",
this->_camera_id, this->_width, this->_height, this->_fps);
this->_cap.open(pipe, cv::CAP_GSTREAMER);
}
else if (this->_type == CameraType::RTSP)
@@ -150,9 +159,12 @@ void Camera::openImpl()
this->_fps = 30;
}
#ifdef PLATFORM_X86_CUDA
sprintf(pipe, "%s?W=%d&H=%d&FPS=%d", this->_rtsp_url.c_str(), this->_width, this->_height, this->_fps);
this->_cap.open(pipe);
#if defined(PLATFORM_X86_CUDA) || defined(PLATFORM_X86_INTEL)
sprintf(pipe, "rtspsrc location=%s?W=%d&H=%d&FPS=%d latency=100 ! \
application/x-rtp,media=video ! rtph264depay ! parsebin ! avdec_h264 ! \
videoconvert ! appsink sync=false",
this->_rtsp_url.c_str(), this->_width, this->_height, this->_fps);
this->_cap.open(pipe, cv::CAP_GSTREAMER);
#endif
#ifdef PLATFORM_JETSON
sprintf(pipe, "rtspsrc location=%s?W=%d&H=%d&FPS=%d latency=100 ! application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false", this->_rtsp_url.c_str(), this->_width, this->_height, this->_fps);

View File

@@ -6,8 +6,13 @@
#include "writer_gstreamer_impl.h"
#endif
#ifdef WITH_FFMPEG
#include "bs_push_streamer.h"
#include "bs_video_saver.h"
#if defined(PLATFORM_X86_CUDA)
#include "x86_cuda/bs_push_streamer.h"
#include "x86_cuda/bs_video_saver.h"
#elif defined(PLATFORM_X86_INTEL)
#include "x86_intel/bs_push_streamer.h"
#include "x86_intel/bs_video_saver.h"
#endif
#endif
@@ -37,10 +42,10 @@ bool VideoWriter::setupImpl(std::string file_name_)
return this->_gstreamer_impl->gstreamerSetup(this, file_name_);
#endif
#ifdef WITH_FFMPEG
#ifdef PLATFORM_X86_CUDA
#if defined(PLATFORM_X86_CUDA)
std::string enc = "h264_nvenc";
#else
std::string enc = "";
#elif defined(PLATFORM_X86_INTEL)
std::string enc = "h264_vaapi";
#endif
return this->_ffmpeg_impl->setup(file_path + file_name_ + ".avi", img_sz.width, img_sz.height, (int)fps, enc, 4);
#endif
@@ -105,10 +110,10 @@ bool VideoStreamer::setupImpl()
#endif
#ifdef WITH_FFMPEG
std::string rtsp_url = "rtsp://127.0.0.1/live" + url;
#ifdef PLATFORM_X86_CUDA
#if defined(PLATFORM_X86_CUDA)
std::string enc = "h264_nvenc";
#else
std::string enc = "";
#elif defined(PLATFORM_X86_INTEL)
std::string enc = "h264_vaapi";
#endif
return this->_ffmpeg_impl->setup(rtsp_url, img_sz.width, img_sz.height, 24, enc, bitrate);
#endif