From fb2a60e3caae7083a2042bd950a28a759e71b0a0 Mon Sep 17 00:00:00 2001 From: Daniel <1367240116@qq.com> Date: Wed, 3 Jan 2024 17:45:48 +0800 Subject: [PATCH] update. --- .../common_det/cuda/common_det_cuda_impl.cpp | 216 +- .../common_det/cuda/common_det_cuda_impl.h | 9 +- algorithm/common_det/sv_common_det.cpp | 8 +- algorithm/sot/ocv470/sot_ocv470_impl.cpp | 4 +- algorithm/sv_algorithm_base.cpp | 2217 +++++++++-------- build_on_jetson.sh | 0 build_on_x86_cuda.sh | 0 build_on_x86_intel.sh | 0 gimbal_ctrl/IOs/serial/README.md | 0 .../IOs/serial/include/serial/impl/unix.h | 0 .../IOs/serial/include/serial/impl/win.h | 0 .../IOs/serial/include/serial/serial.h | 0 .../IOs/serial/include/serial/v8stdint.h | 0 .../src/impl/list_ports/list_ports_linux.cc | 0 .../src/impl/list_ports/list_ports_osx.cc | 0 .../src/impl/list_ports/list_ports_win.cc | 0 gimbal_ctrl/IOs/serial/src/impl/unix.cc | 0 gimbal_ctrl/IOs/serial/src/impl/win.cc | 0 gimbal_ctrl/IOs/serial/src/serial.cc | 0 .../driver/src/AT10/AT10_gimbal_crc32.h | 0 .../driver/src/AT10/AT10_gimbal_driver.cpp | 0 .../driver/src/AT10/AT10_gimbal_driver.h | 0 .../driver/src/AT10/AT10_gimbal_funtion.cpp | 0 .../driver/src/AT10/AT10_gimbal_struct.h | 0 gimbal_ctrl/driver/src/CMakeLists.txt | 0 gimbal_ctrl/driver/src/FIFO/CMakeLists.txt | 0 gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp | 0 gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h | 0 gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h | 0 .../driver/src/G1/g1_gimbal_driver.cpp | 0 gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h | 0 .../driver/src/G1/g1_gimbal_funtion.cpp | 0 gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h | 0 .../driver/src/Q10f/Q10f_gimbal_crc32.h | 0 .../driver/src/Q10f/Q10f_gimbal_driver.cpp | 0 .../driver/src/Q10f/Q10f_gimbal_driver.h | 0 .../driver/src/Q10f/Q10f_gimbal_funtion.cpp | 0 .../driver/src/Q10f/Q10f_gimbal_struct.h | 0 gimbal_ctrl/driver/src/amov_gimbal.cpp | 0 gimbal_ctrl/driver/src/amov_gimbal.h | 0 gimbal_ctrl/driver/src/amov_gimbal_struct.h | 0 include/sv_algorithm_base.h | 8 + include/sv_common_det.h | 3 +- include/sv_video_base.h | 14 + params/a-params/sv_algorithm_params.json | 16 +- samples/calib/calibrate_camera_charuco.cpp | 4 +- samples/demo/aruco_detection.cpp | 8 +- .../demo/detection_with_clicked_tracking.cpp | 10 +- samples/demo/ellipse_detection.cpp | 8 +- ...gimbal_detection_with_clicked_tracking.cpp | 8 +- .../demo/gimbal_landing_marker_detection.cpp | 57 +- .../demo/gimbal_udp_detection_info_sender.cpp | 1 + samples/demo/landing_marker_detection.cpp | 48 +- samples/demo/single_object_tracking.cpp | 11 +- samples/test/camera_fps_test.cpp | 34 + scripts/common/configs-downloading.sh | 39 - scripts/common/ffmpeg425-install.sh | 2 +- scripts/common/gst-install-orin.sh | 1 - scripts/common/gst-install.sh | 1 - .../opencv470-jetpack511-cuda-install.sh | 54 - scripts/test/test_fps.sh | 0 scripts/test/test_gimbal.sh | 0 scripts/x86-cuda/x86-gst-install.sh | 1 - .../x86-cuda/x86-opencv470-cuda-install.sh | 69 - scripts/x86-cuda/x86-opencv470-install.sh | 5 - .../x86-ubuntu2004-cuda-cudnn-11-6.sh | 0 video_io/sv_video_base.cpp | 66 +- video_io/sv_video_input.cpp | 3 +- 68 files changed, 1424 insertions(+), 1501 deletions(-) mode change 100755 => 100644 build_on_jetson.sh mode change 100755 => 100644 build_on_x86_cuda.sh mode change 100755 => 100644 build_on_x86_intel.sh mode change 100755 => 100644 gimbal_ctrl/IOs/serial/README.md mode change 100755 => 100644 gimbal_ctrl/IOs/serial/include/serial/impl/unix.h mode change 100755 => 100644 gimbal_ctrl/IOs/serial/include/serial/impl/win.h mode change 100755 => 100644 gimbal_ctrl/IOs/serial/include/serial/serial.h mode change 100755 => 100644 gimbal_ctrl/IOs/serial/include/serial/v8stdint.h mode change 100755 => 100644 gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_linux.cc mode change 100755 => 100644 gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_osx.cc mode change 100755 => 100644 gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_win.cc mode change 100755 => 100644 gimbal_ctrl/IOs/serial/src/impl/unix.cc mode change 100755 => 100644 gimbal_ctrl/IOs/serial/src/impl/win.cc mode change 100755 => 100644 gimbal_ctrl/IOs/serial/src/serial.cc mode change 100755 => 100644 gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h mode change 100755 => 100644 gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp mode change 100755 => 100644 gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h mode change 100755 => 100644 gimbal_ctrl/driver/src/AT10/AT10_gimbal_funtion.cpp mode change 100755 => 100644 gimbal_ctrl/driver/src/AT10/AT10_gimbal_struct.h mode change 100755 => 100644 gimbal_ctrl/driver/src/CMakeLists.txt mode change 100755 => 100644 gimbal_ctrl/driver/src/FIFO/CMakeLists.txt mode change 100755 => 100644 gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp mode change 100755 => 100644 gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h mode change 100755 => 100644 gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h mode change 100755 => 100644 gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp mode change 100755 => 100644 gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h mode change 100755 => 100644 gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp mode change 100755 => 100644 gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h mode change 100755 => 100644 gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h mode change 100755 => 100644 gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp mode change 100755 => 100644 gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h mode change 100755 => 100644 gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp mode change 100755 => 100644 gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h mode change 100755 => 100644 gimbal_ctrl/driver/src/amov_gimbal.cpp mode change 100755 => 100644 gimbal_ctrl/driver/src/amov_gimbal.h mode change 100755 => 100644 gimbal_ctrl/driver/src/amov_gimbal_struct.h create mode 100644 samples/test/camera_fps_test.cpp delete mode 100644 scripts/common/configs-downloading.sh delete mode 100644 scripts/jetson/opencv470-jetpack511-cuda-install.sh mode change 100755 => 100644 scripts/test/test_fps.sh mode change 100755 => 100644 scripts/test/test_gimbal.sh mode change 100755 => 100644 scripts/x86-cuda/x86-gst-install.sh delete mode 100755 scripts/x86-cuda/x86-opencv470-cuda-install.sh mode change 100755 => 100644 scripts/x86-cuda/x86-opencv470-install.sh mode change 100755 => 100644 scripts/x86-cuda/x86-ubuntu2004-cuda-cudnn-11-6.sh diff --git a/algorithm/common_det/cuda/common_det_cuda_impl.cpp b/algorithm/common_det/cuda/common_det_cuda_impl.cpp index 43dcb7b..d86f467 100644 --- a/algorithm/common_det/cuda/common_det_cuda_impl.cpp +++ b/algorithm/common_det/cuda/common_det_cuda_impl.cpp @@ -103,7 +103,7 @@ void infer_seg(IExecutionContext& context, cudaStream_t& stream, void **buffers, CUDA_CHECK(cudaMemcpyAsync(output2, buffers[2], batchSize * kOutputSize2 * sizeof(float), cudaMemcpyDeviceToHost, stream)); cudaStreamSynchronize(stream); } -void CommonObjectDetectorCUDAImpl::_prepare_buffers(int input_h, int input_w, int batchsize) { +void CommonObjectDetectorCUDAImpl::_prepare_buffers(int input_h, int input_w) { assert(this->_engine->getNbBindings() == 2); // In order to bind the buffers, we need to know the names of the input and output tensors. // Note that indices are guaranteed to be less than IEngine::getNbBindings() @@ -112,12 +112,12 @@ void CommonObjectDetectorCUDAImpl::_prepare_buffers(int input_h, int input_w, in assert(inputIndex == 0); assert(outputIndex == 1); // Create GPU buffers on device - CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[0]), batchsize * 3 * input_h * input_w * sizeof(float))); - CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[1]), batchsize * kOutputSize * sizeof(float))); + CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[0]), kBatchSize * 3 * input_h * input_w * sizeof(float))); + CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[1]), kBatchSize * kOutputSize * sizeof(float))); - this->_cpu_output_buffer = new float[batchsize * kOutputSize]; + this->_cpu_output_buffer = new float[kBatchSize * kOutputSize]; } -void CommonObjectDetectorCUDAImpl::_prepare_buffers_seg(int input_h, int input_w, int batchsize) { +void CommonObjectDetectorCUDAImpl::_prepare_buffers_seg(int input_h, int input_w) { assert(this->_engine->getNbBindings() == 3); // In order to bind the buffers, we need to know the names of the input and output tensors. // Note that indices are guaranteed to be less than IEngine::getNbBindings() @@ -129,13 +129,13 @@ void CommonObjectDetectorCUDAImpl::_prepare_buffers_seg(int input_h, int input_w assert(outputIndex2 == 2); // Create GPU buffers on device - CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[0]), batchsize * 3 * input_h * input_w * sizeof(float))); - CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[1]), batchsize * kOutputSize1 * sizeof(float))); - CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[2]), batchsize * kOutputSize2 * sizeof(float))); + CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[0]), kBatchSize * 3 * input_h * input_w * sizeof(float))); + CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[1]), kBatchSize * kOutputSize1 * sizeof(float))); + CUDA_CHECK(cudaMalloc((void**)&(this->_gpu_buffers[2]), kBatchSize * kOutputSize2 * sizeof(float))); // Alloc CPU buffers - this->_cpu_output_buffer1 = new float[batchsize * kOutputSize1]; - this->_cpu_output_buffer2 = new float[batchsize * kOutputSize2]; + this->_cpu_output_buffer1 = new float[kBatchSize * kOutputSize1]; + this->_cpu_output_buffer2 = new float[kBatchSize * kOutputSize2]; } void deserialize_engine(std::string& engine_name, IRuntime** runtime, ICudaEngine** engine, IExecutionContext** context) { std::ifstream file(engine_name, std::ios::binary); @@ -172,8 +172,7 @@ void CommonObjectDetectorCUDAImpl::cudaDetect( std::vector& boxes_h_, std::vector& boxes_label_, std::vector& boxes_score_, - std::vector& boxes_seg_, - bool input_4k_ + std::vector& boxes_seg_ ) { #ifdef WITH_CUDA @@ -184,51 +183,9 @@ void CommonObjectDetectorCUDAImpl::cudaDetect( double thrs_nms = base_->getThrsNms(); std::vector img_batch; - if (input_4k_) - { - if (img_.cols == 3840 && img_.rows == 2160) - { - cv::Mat patch1, patch2, patch3, patch4, patch5, patch6; - - img_.colRange(200, 1480).rowRange(0, 1280).copyTo(patch1); - img_.colRange(1280, 2560).rowRange(0, 1280).copyTo(patch2); - img_.colRange(2360, 3640).rowRange(0, 1280).copyTo(patch3); - - img_.colRange(200, 1480).rowRange(880, 2160).copyTo(patch4); - img_.colRange(1280, 2560).rowRange(880, 2160).copyTo(patch5); - img_.colRange(2360, 3640).rowRange(880, 2160).copyTo(patch6); - - img_batch.push_back(patch1); - img_batch.push_back(patch2); - img_batch.push_back(patch3); - img_batch.push_back(patch4); - img_batch.push_back(patch5); - img_batch.push_back(patch6); - } - else - { - throw std::runtime_error("SpireCV (106) Input image is NOT 4K (3840 x 2160)!"); - } - if (with_segmentation) - { - throw std::runtime_error("SpireCV (106) Resolution 4K DO NOT Support Segmentation!"); - } - } - else - { - img_batch.push_back(img_); - } - - if (input_4k_) - { - // Preprocess - cuda_batch_preprocess(img_batch, this->_gpu_buffers[0], 1280, 1280, this->_stream); - } - else - { - // Preprocess - cuda_batch_preprocess(img_batch, this->_gpu_buffers[0], input_w, input_h, this->_stream); - } + img_batch.push_back(img_); + // Preprocess + cuda_batch_preprocess(img_batch, this->_gpu_buffers[0], input_w, input_h, this->_stream); // Run inference if (with_segmentation) @@ -237,14 +194,7 @@ void CommonObjectDetectorCUDAImpl::cudaDetect( } else { - if (input_4k_) - { - infer(*this->_context, this->_stream, (void**)this->_gpu_buffers, this->_cpu_output_buffer, 6); - } - else - { - infer(*this->_context, this->_stream, (void**)this->_gpu_buffers, this->_cpu_output_buffer, kBatchSize); - } + infer(*this->_context, this->_stream, (void**)this->_gpu_buffers, this->_cpu_output_buffer, kBatchSize); } // NMS @@ -258,102 +208,45 @@ void CommonObjectDetectorCUDAImpl::cudaDetect( batch_nms(res_batch, this->_cpu_output_buffer, img_batch.size(), kOutputSize, thrs_conf, thrs_nms); } - - if (input_4k_) + std::vector res = res_batch[0]; + std::vector masks; + if (with_segmentation) { - for (size_t k = 0; k < res_batch.size(); k++) - { - std::vector res = res_batch[k]; - for (size_t j = 0; j < res.size(); j++) - { - cv::Rect r = get_rect(img_batch[k], res[j].bbox, 1280, 1280); - if (r.x < 0) r.x = 0; - if (r.y < 0) r.y = 0; - if (r.x + r.width >= 1280) r.width = 1280 - r.x - 1; - if (r.y + r.height >= 1280) r.height = 1280 - r.y - 1; - if (r.width > 3 && r.height > 3) - { - if (0 == k) - { - boxes_x_.push_back(r.x + 200); - boxes_y_.push_back(r.y); - } - else if (1 == k) - { - boxes_x_.push_back(r.x + 1280); - boxes_y_.push_back(r.y); - } - else if (2 == k) - { - boxes_x_.push_back(r.x + 2360); - boxes_y_.push_back(r.y); - } - else if (3 == k) - { - boxes_x_.push_back(r.x + 200); - boxes_y_.push_back(r.y + 880); - } - else if (4 == k) - { - boxes_x_.push_back(r.x + 1280); - boxes_y_.push_back(r.y + 880); - } - else if (5 == k) - { - boxes_x_.push_back(r.x + 2360); - boxes_y_.push_back(r.y + 880); - } - boxes_w_.push_back(r.width); - boxes_h_.push_back(r.height); + masks = process_mask(&(this->_cpu_output_buffer2[0]), kOutputSize2, res, input_h, input_w); + } - boxes_label_.push_back((int)res[j].class_id); - boxes_score_.push_back(res[j].conf); - } + + + for (size_t j = 0; j < res.size(); j++) { + cv::Rect r = get_rect(img_, res[j].bbox, input_h, input_w); + if (r.x < 0) r.x = 0; + if (r.y < 0) r.y = 0; + if (r.x + r.width >= img_.cols) r.width = img_.cols - r.x - 1; + if (r.y + r.height >= img_.rows) r.height = img_.rows - r.y - 1; + if (r.width > 5 && r.height > 5) + { + // cv::rectangle(img_show, r, cv::Scalar(0, 0, 255), 2); + // cv::putText(img_show, vehiclenames[(int)res[j].class_id], cv::Point(r.x, r.y - 1), cv::FONT_HERSHEY_PLAIN, 2.2, cv::Scalar(0, 0, 255), 2); + boxes_x_.push_back(r.x); + boxes_y_.push_back(r.y); + boxes_w_.push_back(r.width); + boxes_h_.push_back(r.height); + + boxes_label_.push_back((int)res[j].class_id); + boxes_score_.push_back(res[j].conf); + + if (with_segmentation) + { + cv::Mat mask_j = masks[j].clone(); + boxes_seg_.push_back(mask_j); } } } - else - { - - std::vector res = res_batch[0]; - std::vector masks; - if (with_segmentation) - { - masks = process_mask(&(this->_cpu_output_buffer2[0]), kOutputSize2, res, input_h, input_w); - } - - for (size_t j = 0; j < res.size(); j++) - { - cv::Rect r = get_rect(img_, res[j].bbox, input_h, input_w); - if (r.x < 0) r.x = 0; - if (r.y < 0) r.y = 0; - if (r.x + r.width >= img_.cols) r.width = img_.cols - r.x - 1; - if (r.y + r.height >= img_.rows) r.height = img_.rows - r.y - 1; - if (r.width > 5 && r.height > 5) - { - // cv::rectangle(img_show, r, cv::Scalar(0, 0, 255), 2); - // cv::putText(img_show, vehiclenames[(int)res[j].class_id], cv::Point(r.x, r.y - 1), cv::FONT_HERSHEY_PLAIN, 2.2, cv::Scalar(0, 0, 255), 2); - boxes_x_.push_back(r.x); - boxes_y_.push_back(r.y); - boxes_w_.push_back(r.width); - boxes_h_.push_back(r.height); - - boxes_label_.push_back((int)res[j].class_id); - boxes_score_.push_back(res[j].conf); - - if (with_segmentation) - { - cv::Mat mask_j = masks[j].clone(); - boxes_seg_.push_back(mask_j); - } - } - } - } #endif } -bool CommonObjectDetectorCUDAImpl::cudaSetup(CommonObjectDetectorBase* base_, bool input_4k_) +bool CommonObjectDetectorCUDAImpl::cudaSetup(CommonObjectDetectorBase* base_) { #ifdef WITH_CUDA std::string dataset = base_->getDataset(); @@ -379,11 +272,6 @@ bool CommonObjectDetectorCUDAImpl::cudaSetup(CommonObjectDetectorBase* base_, bo { throw std::runtime_error("SpireCV (104) Error loading the CommonObject TensorRT model (File Not Exist)"); } - - if (input_4k_ && with_segmentation) - { - throw std::runtime_error("SpireCV (106) Resolution 4K DO NOT Support Segmentation!"); - } deserialize_engine(engine_fn, &this->_runtime, &this->_engine, &this->_context); CUDA_CHECK(cudaStreamCreate(&this->_stream)); @@ -394,20 +282,12 @@ bool CommonObjectDetectorCUDAImpl::cudaSetup(CommonObjectDetectorBase* base_, bo if (with_segmentation) { // Prepare cpu and gpu buffers - this->_prepare_buffers_seg(input_h, input_w, 1); + this->_prepare_buffers_seg(input_h, input_w); } else { - if (input_4k_) - { - // Prepare cpu and gpu buffers - this->_prepare_buffers(input_h, input_w, 6); - } - else - { - // Prepare cpu and gpu buffers - this->_prepare_buffers(input_h, input_w, 1); - } + // Prepare cpu and gpu buffers + this->_prepare_buffers(input_h, input_w); } return true; #endif diff --git a/algorithm/common_det/cuda/common_det_cuda_impl.h b/algorithm/common_det/cuda/common_det_cuda_impl.h index 1b7ae43..cb44faf 100644 --- a/algorithm/common_det/cuda/common_det_cuda_impl.h +++ b/algorithm/common_det/cuda/common_det_cuda_impl.h @@ -26,7 +26,7 @@ public: CommonObjectDetectorCUDAImpl(); ~CommonObjectDetectorCUDAImpl(); - bool cudaSetup(CommonObjectDetectorBase* base_, bool input_4k_); + bool cudaSetup(CommonObjectDetectorBase* base_); void cudaDetect( CommonObjectDetectorBase* base_, cv::Mat img_, @@ -36,13 +36,12 @@ public: std::vector& boxes_h_, std::vector& boxes_label_, std::vector& boxes_score_, - std::vector& boxes_seg_, - bool input_4k_ + std::vector& boxes_seg_ ); #ifdef WITH_CUDA - void _prepare_buffers_seg(int input_h, int input_w, int batchsize); - void _prepare_buffers(int input_h, int input_w, int batchsize); + void _prepare_buffers_seg(int input_h, int input_w); + void _prepare_buffers(int input_h, int input_w); nvinfer1::IExecutionContext* _context; nvinfer1::IRuntime* _runtime; nvinfer1::ICudaEngine* _engine; diff --git a/algorithm/common_det/sv_common_det.cpp b/algorithm/common_det/sv_common_det.cpp index 328a1bf..3a540ca 100644 --- a/algorithm/common_det/sv_common_det.cpp +++ b/algorithm/common_det/sv_common_det.cpp @@ -12,9 +12,8 @@ namespace sv { -CommonObjectDetector::CommonObjectDetector(bool input_4k) +CommonObjectDetector::CommonObjectDetector() { - this->_input_4k = input_4k; #ifdef WITH_CUDA this->_cuda_impl = new CommonObjectDetectorCUDAImpl; #endif @@ -26,7 +25,7 @@ CommonObjectDetector::~CommonObjectDetector() bool CommonObjectDetector::setupImpl() { #ifdef WITH_CUDA - return this->_cuda_impl->cudaSetup(this, this->_input_4k); + return this->_cuda_impl->cudaSetup(this); #endif return false; } @@ -52,8 +51,7 @@ void CommonObjectDetector::detectImpl( boxes_h_, boxes_label_, boxes_score_, - boxes_seg_, - this->_input_4k + boxes_seg_ ); #endif } diff --git a/algorithm/sot/ocv470/sot_ocv470_impl.cpp b/algorithm/sot/ocv470/sot_ocv470_impl.cpp index b711f2e..2836eb8 100644 --- a/algorithm/sot/ocv470/sot_ocv470_impl.cpp +++ b/algorithm/sot/ocv470/sot_ocv470_impl.cpp @@ -39,8 +39,8 @@ bool SingleObjectTrackerOCV470Impl::ocv470Setup(SingleObjectTrackerBase* base_) TrackerNano::Params nano_params; nano_params.backbone = samples::findFile(backbone); nano_params.neckhead = samples::findFile(neckhead); - nano_params.backend = this->_backend; - nano_params.target = this->_target; + nano_params.backend = cv::dnn::DNN_BACKEND_CUDA; + nano_params.target = cv::dnn::DNN_TARGET_CUDA; _nano = TrackerNano::create(nano_params); } diff --git a/algorithm/sv_algorithm_base.cpp b/algorithm/sv_algorithm_base.cpp index f99142f..0633286 100644 --- a/algorithm/sv_algorithm_base.cpp +++ b/algorithm/sv_algorithm_base.cpp @@ -11,1132 +11,1241 @@ #define SV_MODEL_DIR "/SpireCV/models/" #define SV_ROOT_DIR "/SpireCV/" - -namespace sv { - -using namespace cv; -using namespace cv::dnn; - - -void _cameraMatrix2Fov(cv::Mat camera_matrix_, int img_w_, int img_h_, double& fov_x_, double& fov_y_) +namespace sv { - fov_x_ = 2 * atan(img_w_ / 2. / camera_matrix_.at(0, 0)) * SV_RAD2DEG; - fov_y_ = 2 * atan(img_h_ / 2. / camera_matrix_.at(1, 1)) * SV_RAD2DEG; -} + using namespace cv; + using namespace cv::dnn; - -CameraAlgorithm::CameraAlgorithm() -{ - // this->_value = NULL; - // this->_allocator = NULL; - this->_t0 = std::chrono::system_clock::now(); - - this->alg_params_fn = _get_home() + SV_ROOT_DIR + "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); -} -CameraAlgorithm::~CameraAlgorithm() -{ - // if (_value) delete _value; - // if (_allocator) delete _allocator; -} - -void CameraAlgorithm::loadCameraParams(std::string yaml_fn_) -{ - cv::FileStorage fs(yaml_fn_, cv::FileStorage::READ); - if (!fs.isOpened()) + void _cameraMatrix2Fov(cv::Mat camera_matrix_, int img_w_, int img_h_, double &fov_x_, double &fov_y_) { - throw std::runtime_error("SpireCV (104) Camera calib file NOT exist!"); + fov_x_ = 2 * atan(img_w_ / 2. / camera_matrix_.at(0, 0)) * SV_RAD2DEG; + fov_y_ = 2 * atan(img_h_ / 2. / camera_matrix_.at(1, 1)) * SV_RAD2DEG; } - fs["camera_matrix"] >> this->camera_matrix; - fs["distortion_coefficients"] >> this->distortion; - fs["image_width"] >> this->image_width; - fs["image_height"] >> this->image_height; - - if (this->camera_matrix.rows != 3 || this->camera_matrix.cols != 3 || - this->distortion.rows != 1 || this->distortion.cols != 5 || - this->image_width == 0 || this->image_height == 0) + + CameraAlgorithm::CameraAlgorithm() { - throw std::runtime_error("SpireCV (106) Camera parameters reading ERROR!"); + // this->_value = NULL; + // this->_allocator = NULL; + this->_t0 = std::chrono::system_clock::now(); + + this->alg_params_fn = _get_home() + SV_ROOT_DIR + "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); } - - _cameraMatrix2Fov(this->camera_matrix, this->image_width, this->image_height, this->fov_x, this->fov_y); - // std::cout << this->fov_x << ", " << this->fov_y << std::endl; -} - - -void CameraAlgorithm::loadAlgorithmParams(std::string json_fn_) -{ - this->alg_params_fn = json_fn_; -} - - -ArucoDetector::ArucoDetector() -{ - _params_loaded = false; - _dictionary = nullptr; -} - - -void ArucoDetector::_load() -{ - JsonValue all_value; - JsonAllocator allocator; - std::cout << "Load: [" << this->alg_params_fn << "]" << std::endl; - _load_all_json(this->alg_params_fn, all_value, allocator); - - JsonValue aruco_params_value; - _parser_algorithm_params("ArucoDetector", all_value, aruco_params_value); - - _dictionary_id = 10; - // _detector_params = aruco::DetectorParameters::create(); - _detector_params = new aruco::DetectorParameters; - for (auto i : aruco_params_value) { - if ("_dictionary_id" == std::string(i->key)) { - _dictionary_id = i->value.toNumber(); - } - else if ("adaptiveThreshConstant" == std::string(i->key)) { - // std::cout << "adaptiveThreshConstant (old, new): " << _detector_params->adaptiveThreshConstant << ", " << i->value.toNumber() << std::endl; - _detector_params->adaptiveThreshConstant = i->value.toNumber(); - } - else if ("adaptiveThreshWinSizeMax" == std::string(i->key)) { - // std::cout << "adaptiveThreshWinSizeMax (old, new): " << _detector_params->adaptiveThreshWinSizeMax << ", " << i->value.toNumber() << std::endl; - _detector_params->adaptiveThreshWinSizeMax = i->value.toNumber(); - } - else if ("adaptiveThreshWinSizeMin" == std::string(i->key)) { - // std::cout << "adaptiveThreshWinSizeMin (old, new): " << _detector_params->adaptiveThreshWinSizeMin << ", " << i->value.toNumber() << std::endl; - _detector_params->adaptiveThreshWinSizeMin = i->value.toNumber(); - } - else if ("adaptiveThreshWinSizeStep" == std::string(i->key)) { - // std::cout << "adaptiveThreshWinSizeStep (old, new): " << _detector_params->adaptiveThreshWinSizeStep << ", " << i->value.toNumber() << std::endl; - _detector_params->adaptiveThreshWinSizeStep = i->value.toNumber(); - } - else if ("aprilTagCriticalRad" == std::string(i->key)) { - // std::cout << "aprilTagCriticalRad (old, new): " << _detector_params->aprilTagCriticalRad << ", " << i->value.toNumber() << std::endl; - _detector_params->aprilTagCriticalRad = i->value.toNumber(); - } - else if ("aprilTagDeglitch" == std::string(i->key)) { - // std::cout << "aprilTagDeglitch (old, new): " << _detector_params->aprilTagDeglitch << ", " << i->value.toNumber() << std::endl; - _detector_params->aprilTagDeglitch = i->value.toNumber(); - } - else if ("aprilTagMaxLineFitMse" == std::string(i->key)) { - // std::cout << "aprilTagMaxLineFitMse (old, new): " << _detector_params->aprilTagMaxLineFitMse << ", " << i->value.toNumber() << std::endl; - _detector_params->aprilTagMaxLineFitMse = i->value.toNumber(); - } - else if ("aprilTagMaxNmaxima" == std::string(i->key)) { - // std::cout << "aprilTagMaxNmaxima (old, new): " << _detector_params->aprilTagMaxNmaxima << ", " << i->value.toNumber() << std::endl; - _detector_params->aprilTagMaxNmaxima = i->value.toNumber(); - } - else if ("aprilTagMinClusterPixels" == std::string(i->key)) { - // std::cout << "aprilTagMinClusterPixels (old, new): " << _detector_params->aprilTagMinClusterPixels << ", " << i->value.toNumber() << std::endl; - _detector_params->aprilTagMinClusterPixels = i->value.toNumber(); - } - else if ("aprilTagMinWhiteBlackDiff" == std::string(i->key)) { - // std::cout << "aprilTagMinWhiteBlackDiff (old, new): " << _detector_params->aprilTagMinWhiteBlackDiff << ", " << i->value.toNumber() << std::endl; - _detector_params->aprilTagMinWhiteBlackDiff = i->value.toNumber(); - } - else if ("aprilTagQuadDecimate" == std::string(i->key)) { - // std::cout << "aprilTagQuadDecimate (old, new): " << _detector_params->aprilTagQuadDecimate << ", " << i->value.toNumber() << std::endl; - _detector_params->aprilTagQuadDecimate = i->value.toNumber(); - } - else if ("aprilTagQuadSigma" == std::string(i->key)) { - // std::cout << "aprilTagQuadSigma (old, new): " << _detector_params->aprilTagQuadSigma << ", " << i->value.toNumber() << std::endl; - _detector_params->aprilTagQuadSigma = i->value.toNumber(); - } - else if ("cornerRefinementMaxIterations" == std::string(i->key)) { - // std::cout << "cornerRefinementMaxIterations (old, new): " << _detector_params->cornerRefinementMaxIterations << ", " << i->value.toNumber() << std::endl; - _detector_params->cornerRefinementMaxIterations = i->value.toNumber(); - } - else if ("cornerRefinementMethod" == std::string(i->key)) { - // std::cout << "cornerRefinementMethod (old, new): " << _detector_params->cornerRefinementMethod << ", " << i->value.toNumber() << std::endl; - // _detector_params->cornerRefinementMethod = i->value.toNumber(); - int method = (int) i->value.toNumber(); - if (method == 1) - { - _detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_SUBPIX; - } - else if (method == 2) - { - _detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_CONTOUR; - } - else if (method == 3) - { - _detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_APRILTAG; - } - else - { - _detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_NONE; - } - } - else if ("cornerRefinementMinAccuracy" == std::string(i->key)) { - // std::cout << "cornerRefinementMinAccuracy (old, new): " << _detector_params->cornerRefinementMinAccuracy << ", " << i->value.toNumber() << std::endl; - _detector_params->cornerRefinementMinAccuracy = i->value.toNumber(); - } - else if ("cornerRefinementWinSize" == std::string(i->key)) { - // std::cout << "cornerRefinementWinSize (old, new): " << _detector_params->cornerRefinementWinSize << ", " << i->value.toNumber() << std::endl; - _detector_params->cornerRefinementWinSize = i->value.toNumber(); - } - else if ("detectInvertedMarker" == std::string(i->key)) { - bool json_tf = false; - if (i->value.getTag() == JSON_TRUE) json_tf = true; - // std::cout << "detectInvertedMarker (old, new): " << _detector_params->detectInvertedMarker << ", " << json_tf << std::endl; - _detector_params->detectInvertedMarker = json_tf; - } - else if ("errorCorrectionRate" == std::string(i->key)) { - // std::cout << "errorCorrectionRate (old, new): " << _detector_params->errorCorrectionRate << ", " << i->value.toNumber() << std::endl; - _detector_params->errorCorrectionRate = i->value.toNumber(); - } - else if ("markerBorderBits" == std::string(i->key)) { - // std::cout << "markerBorderBits (old, new): " << _detector_params->markerBorderBits << ", " << i->value.toNumber() << std::endl; - _detector_params->markerBorderBits = i->value.toNumber(); - } - else if ("maxErroneousBitsInBorderRate" == std::string(i->key)) { - // std::cout << "maxErroneousBitsInBorderRate (old, new): " << _detector_params->maxErroneousBitsInBorderRate << ", " << i->value.toNumber() << std::endl; - _detector_params->maxErroneousBitsInBorderRate = i->value.toNumber(); - } - else if ("maxMarkerPerimeterRate" == std::string(i->key)) { - // std::cout << "maxMarkerPerimeterRate (old, new): " << _detector_params->maxMarkerPerimeterRate << ", " << i->value.toNumber() << std::endl; - _detector_params->maxMarkerPerimeterRate = i->value.toNumber(); - } - else if ("minCornerDistanceRate" == std::string(i->key)) { - // std::cout << "minCornerDistanceRate (old, new): " << _detector_params->minCornerDistanceRate << ", " << i->value.toNumber() << std::endl; - _detector_params->minCornerDistanceRate = i->value.toNumber(); - } - else if ("minDistanceToBorder" == std::string(i->key)) { - // std::cout << "minDistanceToBorder (old, new): " << _detector_params->minDistanceToBorder << ", " << i->value.toNumber() << std::endl; - _detector_params->minDistanceToBorder = i->value.toNumber(); - } - else if ("minMarkerDistanceRate" == std::string(i->key)) { - // std::cout << "minMarkerDistanceRate (old, new): " << _detector_params->minMarkerDistanceRate << ", " << i->value.toNumber() << std::endl; - _detector_params->minMarkerDistanceRate = i->value.toNumber(); - } - else if ("minMarkerLengthRatioOriginalImg" == std::string(i->key)) { - // std::cout << "minMarkerLengthRatioOriginalImg (old, new): " << _detector_params->minMarkerLengthRatioOriginalImg << ", " << i->value.toNumber() << std::endl; - _detector_params->minMarkerLengthRatioOriginalImg = i->value.toNumber(); - } - else if ("minMarkerPerimeterRate" == std::string(i->key)) { - // std::cout << "minMarkerPerimeterRate (old, new): " << _detector_params->minMarkerPerimeterRate << ", " << i->value.toNumber() << std::endl; - _detector_params->minMarkerPerimeterRate = i->value.toNumber(); - } - else if ("minOtsuStdDev" == std::string(i->key)) { - // std::cout << "minOtsuStdDev (old, new): " << _detector_params->minOtsuStdDev << ", " << i->value.toNumber() << std::endl; - _detector_params->minOtsuStdDev = i->value.toNumber(); - } - else if ("minSideLengthCanonicalImg" == std::string(i->key)) { - // std::cout << "minSideLengthCanonicalImg (old, new): " << _detector_params->minSideLengthCanonicalImg << ", " << i->value.toNumber() << std::endl; - _detector_params->minSideLengthCanonicalImg = i->value.toNumber(); - } - else if ("perspectiveRemoveIgnoredMarginPerCell" == std::string(i->key)) { - // std::cout << "perspectiveRemoveIgnoredMarginPerCell (old, new): " << _detector_params->perspectiveRemoveIgnoredMarginPerCell << ", " << i->value.toNumber() << std::endl; - _detector_params->perspectiveRemoveIgnoredMarginPerCell = i->value.toNumber(); - } - else if ("perspectiveRemovePixelPerCell" == std::string(i->key)) { - // std::cout << "perspectiveRemovePixelPerCell (old, new): " << _detector_params->perspectiveRemovePixelPerCell << ", " << i->value.toNumber() << std::endl; - _detector_params->perspectiveRemovePixelPerCell = i->value.toNumber(); - } - else if ("polygonalApproxAccuracyRate" == std::string(i->key)) { - // std::cout << "polygonalApproxAccuracyRate (old, new): " << _detector_params->polygonalApproxAccuracyRate << ", " << i->value.toNumber() << std::endl; - _detector_params->polygonalApproxAccuracyRate = i->value.toNumber(); - } - else if ("useAruco3Detection" == std::string(i->key)) { - bool json_tf = false; - if (i->value.getTag() == JSON_TRUE) json_tf = true; - // std::cout << "useAruco3Detection (old, new): " << _detector_params->useAruco3Detection << ", " << json_tf << std::endl; - _detector_params->useAruco3Detection = json_tf; - } - else if ("markerIds" == std::string(i->key) && i->value.getTag() == JSON_ARRAY) { - int jcnt = 0; - for (auto j : i->value) { - if (jcnt == 0 && j->value.toNumber() == -1) { - _ids_need.push_back(-1); - break; - } - else { - _ids_need.push_back(j->value.toNumber()); - } - } - } - else if ("markerLengths" == std::string(i->key) && i->value.getTag() == JSON_ARRAY) { - for (auto j : i->value) { - if (_ids_need.size() > 0 && _ids_need[0] == -1) { - _lengths_need.push_back(j->value.toNumber()); - break; - } - else { - _lengths_need.push_back(j->value.toNumber()); - } - } - } - } - - if (_ids_need.size() == 0) _ids_need.push_back(-1); - if (_lengths_need.size() != _ids_need.size()) { - throw std::runtime_error("SpireCV (106) Parameter markerIds.length != markerLengths.length!"); - } - - // for (int id : _ids_need) - // std::cout << "_ids_need: " << id << std::endl; - // for (double l : _lengths_need) - // std::cout << "_lengths_need: " << l << std::endl; -} - - -void ArucoDetector::detect(cv::Mat img_, TargetsInFrame& tgts_) -{ - if (!_params_loaded) + CameraAlgorithm::~CameraAlgorithm() { - this->_load(); - _params_loaded = true; - } - if (img_.cols != this->image_width || img_.rows != this->image_height) - { - char msg[256]; - sprintf(msg, "SpireCV (106) Calib camera SIZE(%d) != Input image SIZE(%d)!", this->image_width, img_.cols); - throw std::runtime_error(msg); - } - // std::cout << "_dictionary_id: " << _dictionary_id << std::endl; - // Ptr dictionary = aruco::getPredefinedDictionary(aruco::PredefinedDictionaryType(_dictionary_id)); - if (this->_dictionary == nullptr) - { - this->_dictionary = new aruco::Dictionary; - *(this->_dictionary) = aruco::getPredefinedDictionary(aruco::PredefinedDictionaryType(_dictionary_id)); + // if (_value) delete _value; + // if (_allocator) delete _allocator; } - std::vector ids, ids_final; - std::vector > corners, corners_final, rejected; - std::vector rvecs, tvecs; - - // detect markers and estimate pose - aruco::detectMarkers(img_, this->_dictionary, corners, ids, _detector_params, rejected); - - - if (ids.size() > 0) + void CameraAlgorithm::loadCameraParams(std::string yaml_fn_) { - if (_ids_need[0] == -1) + cv::FileStorage fs(yaml_fn_, cv::FileStorage::READ); + if (!fs.isOpened()) { - // std::cout << this->camera_matrix << std::endl; - aruco::estimatePoseSingleMarkers(corners, _lengths_need[0], this->camera_matrix, this->distortion, rvecs, tvecs); - ids_final = ids; - corners_final = corners; + throw std::runtime_error("SpireCV (104) Camera calib file NOT exist!"); } - else + fs["camera_matrix"] >> this->camera_matrix; + fs["distortion_coefficients"] >> this->distortion; + fs["image_width"] >> this->image_width; + fs["image_height"] >> this->image_height; + + if (this->camera_matrix.rows != 3 || this->camera_matrix.cols != 3 || + this->distortion.rows != 1 || this->distortion.cols != 5 || + this->image_width == 0 || this->image_height == 0) { - for (int i=0; i<_ids_need.size(); i++) + throw std::runtime_error("SpireCV (106) Camera parameters reading ERROR!"); + } + + _cameraMatrix2Fov(this->camera_matrix, this->image_width, this->image_height, this->fov_x, this->fov_y); + // std::cout << this->fov_x << ", " << this->fov_y << std::endl; + } + + void CameraAlgorithm::loadAlgorithmParams(std::string json_fn_) + { + this->alg_params_fn = json_fn_; + } + + ArucoDetector::ArucoDetector() + { + _params_loaded = false; + _dictionary = nullptr; + } + + void ArucoDetector::_load() + { + JsonValue all_value; + JsonAllocator allocator; + std::cout << "Load: [" << this->alg_params_fn << "]" << std::endl; + _load_all_json(this->alg_params_fn, all_value, allocator); + + JsonValue aruco_params_value; + _parser_algorithm_params("ArucoDetector", all_value, aruco_params_value); + + _dictionary_id = 10; + // _detector_params = aruco::DetectorParameters::create(); + _detector_params = new aruco::DetectorParameters; + for (auto i : aruco_params_value) + { + if ("_dictionary_id" == std::string(i->key)) { - int id_need = _ids_need[i]; - double length_need = _lengths_need[i]; - std::vector t_rvecs, t_tvecs; - std::vector > t_corners; - for (int j=0; jvalue.toNumber(); + } + else if ("adaptiveThreshConstant" == std::string(i->key)) + { + // std::cout << "adaptiveThreshConstant (old, new): " << _detector_params->adaptiveThreshConstant << ", " << i->value.toNumber() << std::endl; + _detector_params->adaptiveThreshConstant = i->value.toNumber(); + } + else if ("adaptiveThreshWinSizeMax" == std::string(i->key)) + { + // std::cout << "adaptiveThreshWinSizeMax (old, new): " << _detector_params->adaptiveThreshWinSizeMax << ", " << i->value.toNumber() << std::endl; + _detector_params->adaptiveThreshWinSizeMax = i->value.toNumber(); + } + else if ("adaptiveThreshWinSizeMin" == std::string(i->key)) + { + // std::cout << "adaptiveThreshWinSizeMin (old, new): " << _detector_params->adaptiveThreshWinSizeMin << ", " << i->value.toNumber() << std::endl; + _detector_params->adaptiveThreshWinSizeMin = i->value.toNumber(); + } + else if ("adaptiveThreshWinSizeStep" == std::string(i->key)) + { + // std::cout << "adaptiveThreshWinSizeStep (old, new): " << _detector_params->adaptiveThreshWinSizeStep << ", " << i->value.toNumber() << std::endl; + _detector_params->adaptiveThreshWinSizeStep = i->value.toNumber(); + } + else if ("aprilTagCriticalRad" == std::string(i->key)) + { + // std::cout << "aprilTagCriticalRad (old, new): " << _detector_params->aprilTagCriticalRad << ", " << i->value.toNumber() << std::endl; + _detector_params->aprilTagCriticalRad = i->value.toNumber(); + } + else if ("aprilTagDeglitch" == std::string(i->key)) + { + // std::cout << "aprilTagDeglitch (old, new): " << _detector_params->aprilTagDeglitch << ", " << i->value.toNumber() << std::endl; + _detector_params->aprilTagDeglitch = i->value.toNumber(); + } + else if ("aprilTagMaxLineFitMse" == std::string(i->key)) + { + // std::cout << "aprilTagMaxLineFitMse (old, new): " << _detector_params->aprilTagMaxLineFitMse << ", " << i->value.toNumber() << std::endl; + _detector_params->aprilTagMaxLineFitMse = i->value.toNumber(); + } + else if ("aprilTagMaxNmaxima" == std::string(i->key)) + { + // std::cout << "aprilTagMaxNmaxima (old, new): " << _detector_params->aprilTagMaxNmaxima << ", " << i->value.toNumber() << std::endl; + _detector_params->aprilTagMaxNmaxima = i->value.toNumber(); + } + else if ("aprilTagMinClusterPixels" == std::string(i->key)) + { + // std::cout << "aprilTagMinClusterPixels (old, new): " << _detector_params->aprilTagMinClusterPixels << ", " << i->value.toNumber() << std::endl; + _detector_params->aprilTagMinClusterPixels = i->value.toNumber(); + } + else if ("aprilTagMinWhiteBlackDiff" == std::string(i->key)) + { + // std::cout << "aprilTagMinWhiteBlackDiff (old, new): " << _detector_params->aprilTagMinWhiteBlackDiff << ", " << i->value.toNumber() << std::endl; + _detector_params->aprilTagMinWhiteBlackDiff = i->value.toNumber(); + } + else if ("aprilTagQuadDecimate" == std::string(i->key)) + { + // std::cout << "aprilTagQuadDecimate (old, new): " << _detector_params->aprilTagQuadDecimate << ", " << i->value.toNumber() << std::endl; + _detector_params->aprilTagQuadDecimate = i->value.toNumber(); + } + else if ("aprilTagQuadSigma" == std::string(i->key)) + { + // std::cout << "aprilTagQuadSigma (old, new): " << _detector_params->aprilTagQuadSigma << ", " << i->value.toNumber() << std::endl; + _detector_params->aprilTagQuadSigma = i->value.toNumber(); + } + else if ("cornerRefinementMaxIterations" == std::string(i->key)) + { + // std::cout << "cornerRefinementMaxIterations (old, new): " << _detector_params->cornerRefinementMaxIterations << ", " << i->value.toNumber() << std::endl; + _detector_params->cornerRefinementMaxIterations = i->value.toNumber(); + } + else if ("cornerRefinementMethod" == std::string(i->key)) + { + // std::cout << "cornerRefinementMethod (old, new): " << _detector_params->cornerRefinementMethod << ", " << i->value.toNumber() << std::endl; + // _detector_params->cornerRefinementMethod = i->value.toNumber(); + int method = (int)i->value.toNumber(); + if (method == 1) { - if (ids[j] == id_need) + _detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_SUBPIX; + } + else if (method == 2) + { + _detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_CONTOUR; + } + else if (method == 3) + { + _detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_APRILTAG; + } + else + { + _detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_NONE; + } + } + else if ("cornerRefinementMinAccuracy" == std::string(i->key)) + { + // std::cout << "cornerRefinementMinAccuracy (old, new): " << _detector_params->cornerRefinementMinAccuracy << ", " << i->value.toNumber() << std::endl; + _detector_params->cornerRefinementMinAccuracy = i->value.toNumber(); + } + else if ("cornerRefinementWinSize" == std::string(i->key)) + { + // std::cout << "cornerRefinementWinSize (old, new): " << _detector_params->cornerRefinementWinSize << ", " << i->value.toNumber() << std::endl; + _detector_params->cornerRefinementWinSize = i->value.toNumber(); + } + else if ("detectInvertedMarker" == std::string(i->key)) + { + bool json_tf = false; + if (i->value.getTag() == JSON_TRUE) + json_tf = true; + // std::cout << "detectInvertedMarker (old, new): " << _detector_params->detectInvertedMarker << ", " << json_tf << std::endl; + _detector_params->detectInvertedMarker = json_tf; + } + else if ("errorCorrectionRate" == std::string(i->key)) + { + // std::cout << "errorCorrectionRate (old, new): " << _detector_params->errorCorrectionRate << ", " << i->value.toNumber() << std::endl; + _detector_params->errorCorrectionRate = i->value.toNumber(); + } + else if ("markerBorderBits" == std::string(i->key)) + { + // std::cout << "markerBorderBits (old, new): " << _detector_params->markerBorderBits << ", " << i->value.toNumber() << std::endl; + _detector_params->markerBorderBits = i->value.toNumber(); + } + else if ("maxErroneousBitsInBorderRate" == std::string(i->key)) + { + // std::cout << "maxErroneousBitsInBorderRate (old, new): " << _detector_params->maxErroneousBitsInBorderRate << ", " << i->value.toNumber() << std::endl; + _detector_params->maxErroneousBitsInBorderRate = i->value.toNumber(); + } + else if ("maxMarkerPerimeterRate" == std::string(i->key)) + { + // std::cout << "maxMarkerPerimeterRate (old, new): " << _detector_params->maxMarkerPerimeterRate << ", " << i->value.toNumber() << std::endl; + _detector_params->maxMarkerPerimeterRate = i->value.toNumber(); + } + else if ("minCornerDistanceRate" == std::string(i->key)) + { + // std::cout << "minCornerDistanceRate (old, new): " << _detector_params->minCornerDistanceRate << ", " << i->value.toNumber() << std::endl; + _detector_params->minCornerDistanceRate = i->value.toNumber(); + } + else if ("minDistanceToBorder" == std::string(i->key)) + { + // std::cout << "minDistanceToBorder (old, new): " << _detector_params->minDistanceToBorder << ", " << i->value.toNumber() << std::endl; + _detector_params->minDistanceToBorder = i->value.toNumber(); + } + else if ("minMarkerDistanceRate" == std::string(i->key)) + { + // std::cout << "minMarkerDistanceRate (old, new): " << _detector_params->minMarkerDistanceRate << ", " << i->value.toNumber() << std::endl; + _detector_params->minMarkerDistanceRate = i->value.toNumber(); + } + else if ("minMarkerLengthRatioOriginalImg" == std::string(i->key)) + { + // std::cout << "minMarkerLengthRatioOriginalImg (old, new): " << _detector_params->minMarkerLengthRatioOriginalImg << ", " << i->value.toNumber() << std::endl; + _detector_params->minMarkerLengthRatioOriginalImg = i->value.toNumber(); + } + else if ("minMarkerPerimeterRate" == std::string(i->key)) + { + // std::cout << "minMarkerPerimeterRate (old, new): " << _detector_params->minMarkerPerimeterRate << ", " << i->value.toNumber() << std::endl; + _detector_params->minMarkerPerimeterRate = i->value.toNumber(); + } + else if ("minOtsuStdDev" == std::string(i->key)) + { + // std::cout << "minOtsuStdDev (old, new): " << _detector_params->minOtsuStdDev << ", " << i->value.toNumber() << std::endl; + _detector_params->minOtsuStdDev = i->value.toNumber(); + } + else if ("minSideLengthCanonicalImg" == std::string(i->key)) + { + // std::cout << "minSideLengthCanonicalImg (old, new): " << _detector_params->minSideLengthCanonicalImg << ", " << i->value.toNumber() << std::endl; + _detector_params->minSideLengthCanonicalImg = i->value.toNumber(); + } + else if ("perspectiveRemoveIgnoredMarginPerCell" == std::string(i->key)) + { + // std::cout << "perspectiveRemoveIgnoredMarginPerCell (old, new): " << _detector_params->perspectiveRemoveIgnoredMarginPerCell << ", " << i->value.toNumber() << std::endl; + _detector_params->perspectiveRemoveIgnoredMarginPerCell = i->value.toNumber(); + } + else if ("perspectiveRemovePixelPerCell" == std::string(i->key)) + { + // std::cout << "perspectiveRemovePixelPerCell (old, new): " << _detector_params->perspectiveRemovePixelPerCell << ", " << i->value.toNumber() << std::endl; + _detector_params->perspectiveRemovePixelPerCell = i->value.toNumber(); + } + else if ("polygonalApproxAccuracyRate" == std::string(i->key)) + { + // std::cout << "polygonalApproxAccuracyRate (old, new): " << _detector_params->polygonalApproxAccuracyRate << ", " << i->value.toNumber() << std::endl; + _detector_params->polygonalApproxAccuracyRate = i->value.toNumber(); + } + else if ("useAruco3Detection" == std::string(i->key)) + { + bool json_tf = false; + if (i->value.getTag() == JSON_TRUE) + json_tf = true; + // std::cout << "useAruco3Detection (old, new): " << _detector_params->useAruco3Detection << ", " << json_tf << std::endl; + _detector_params->useAruco3Detection = json_tf; + } + else if ("markerIds" == std::string(i->key) && i->value.getTag() == JSON_ARRAY) + { + int jcnt = 0; + for (auto j : i->value) + { + if (jcnt == 0 && j->value.toNumber() == -1) { - t_corners.push_back(corners[j]); - ids_final.push_back(ids[j]); - corners_final.push_back(corners[j]); + _ids_need.push_back(-1); + break; + } + else + { + _ids_need.push_back(j->value.toNumber()); } } - if (t_corners.size() > 0) + } + else if ("markerLengths" == std::string(i->key) && i->value.getTag() == JSON_ARRAY) + { + for (auto j : i->value) { - aruco::estimatePoseSingleMarkers(t_corners, length_need, this->camera_matrix, this->distortion, t_rvecs, t_tvecs); - for (auto t_rvec : t_rvecs) - rvecs.push_back(t_rvec); - for (auto t_tvec : t_tvecs) - tvecs.push_back(t_tvec); + if (_ids_need.size() > 0 && _ids_need[0] == -1) + { + _lengths_need.push_back(j->value.toNumber()); + break; + } + else + { + _lengths_need.push_back(j->value.toNumber()); + } } } } - } - // aruco::drawDetectedMarkers(img_, corners_final, ids_final); - tgts_.setSize(img_.cols, img_.rows); - - // tgts_.fov_x = this->fov_x; - // tgts_.fov_y = this->fov_y; - tgts_.setFOV(this->fov_x, this->fov_y); - auto t1 = std::chrono::system_clock::now(); - tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); - this->_t0 = std::chrono::system_clock::now(); - tgts_.setTimeNow(); - - if (ids_final.size() > 0) - { - for (int i=0; icamera_matrix); - tgts_.targets.push_back(tgt); - - // Box b; - // tgt.getBox(b); - // cv::circle(img_, cv::Point(int(corners_final[i][0].x), int(corners_final[i][0].y)), 5, cv::Scalar(0,0,255), 2); - // cv::circle(img_, cv::Point(int(corners_final[i][1].x), int(corners_final[i][1].y)), 5, cv::Scalar(255,0,0), 2); - // cv::rectangle(img_, cv::Rect(b.x1, b.y1, b.x2-b.x1+1, b.y2-b.y1+1), cv::Scalar(0,0,255), 1, 1, 0); + throw std::runtime_error("SpireCV (106) Parameter markerIds.length != markerLengths.length!"); } + + // for (int id : _ids_need) + // std::cout << "_ids_need: " << id << std::endl; + // for (double l : _lengths_need) + // std::cout << "_lengths_need: " << l << std::endl; } - tgts_.type = MissionType::ARUCO_DET; - - // imshow("img", img_); - // waitKey(10); -} - - - -EllipseDetector::EllipseDetector() -{ - this->_ed = NULL; - this->_max_center_distance_ratio = 0.05f; - this->_params_loaded = false; -} -EllipseDetector::~EllipseDetector() -{ - if (_ed) { delete _ed; _ed = NULL; } -} - -void EllipseDetector::detect(cv::Mat img_, TargetsInFrame& tgts_) -{ - if (!_params_loaded) + void ArucoDetector::detect(cv::Mat img_, TargetsInFrame &tgts_) { - this->_load(); - _params_loaded = true; - } - - float fMaxCenterDistance = sqrt(float(img_.cols*img_.cols + img_.rows*img_.rows)) * this->_max_center_distance_ratio; - _ed->SetMCD(fMaxCenterDistance); - std::vector ellsCned; - _ed->Detect(img_, ellsCned); - - tgts_.setSize(img_.cols, img_.rows); - tgts_.setFOV(this->fov_x, this->fov_y); - auto t1 = std::chrono::system_clock::now(); - tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); - this->_t0 = std::chrono::system_clock::now(); - tgts_.setTimeNow(); - - for (yaed::Ellipse ell : ellsCned) - { - Target tgt; - tgt.setEllipse(ell.xc_, ell.yc_, ell.a_, ell.b_, ell.rad_, ell.score_, tgts_.width, tgts_.height, this->camera_matrix, this->_radius_in_meter); - tgts_.targets.push_back(tgt); - } - - tgts_.type = MissionType::ELLIPSE_DET; -} - -LandingMarkerDetectorBase::LandingMarkerDetectorBase() -{ - // this->_params_loaded = false; - // std::string params_fn = _get_home() + SV_ROOT_DIR + "sv_algorithm_params.json"; - // if (_is_file_exist(params_fn)) - // this->loadAlgorithmParams(params_fn); - setupImpl(); -} - - -LandingMarkerDetectorBase::~LandingMarkerDetectorBase() -{ - -} - -bool LandingMarkerDetectorBase::isParamsLoaded() -{ - return this->_params_loaded; -} -int LandingMarkerDetectorBase::getMaxCandidates() -{ - return this->_max_candidates; -} -std::vector LandingMarkerDetectorBase::getLabelsNeed() -{ - return this->_labels_need; -} - - -void LandingMarkerDetectorBase::detect(cv::Mat img_, TargetsInFrame& tgts_) -{ - if (!_params_loaded) - { - this->_load(); - this->_loadLabels(); - _params_loaded = true; - } - - float fMaxCenterDistance = sqrt(float(img_.cols*img_.cols + img_.rows*img_.rows)) * this->_max_center_distance_ratio; - _ed->SetMCD(fMaxCenterDistance); - std::vector ellsCned; - _ed->Detect(img_, ellsCned); - - tgts_.setSize(img_.cols, img_.rows); - tgts_.setFOV(this->fov_x, this->fov_y); - auto t1 = std::chrono::system_clock::now(); - tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); - this->_t0 = std::chrono::system_clock::now(); - tgts_.setTimeNow(); - - static std::vector s_label2str = {"neg", "h", "x", "1", "2", "3", "4", "5", "6", "7", "8"}; - int cand_cnt = 0; - std::vector input_rois; - while (cand_cnt < this->_max_candidates && ellsCned.size() > cand_cnt) - { - yaed::Ellipse e = ellsCned[cand_cnt++]; - - cv::Rect rect; - e.GetRectangle(rect); - int x1 = rect.x; - int y1 = rect.y; - int x2 = rect.x + rect.width; - int y2 = rect.y + rect.height; - if (x1 < 0) x1 = 0; - if (y1 < 0) y1 = 0; - if (x2 > img_.cols - 1) x2 = img_.cols - 1; - if (y2 > img_.rows - 1) y2 = img_.rows - 1; - if (x2 - x1 < 5 || y2 - y1 < 5) continue; - rect.x = x1; - rect.y = y1; - rect.width = x2 - x1; - rect.height = y2 - y1; - - cv::Mat e_roi = img_(rect); - cv::resize(e_roi, e_roi, cv::Size(32, 32)); - - input_rois.push_back(e_roi); - } - - std::vector output_labels; - roiCNN(input_rois, output_labels); - if (input_rois.size() != output_labels.size()) - throw std::runtime_error("SpireCV (106) input_rois.size() != output_labels.size()"); - - for (int i=0; i_labels_need[j] == s_label2str[label]) + this->_load(); + _params_loaded = true; + } + if (img_.cols != this->image_width || img_.rows != this->image_height) + { + char msg[256]; + sprintf(msg, "SpireCV (106) Calib camera SIZE(%d) != Input image SIZE(%d)!", this->image_width, img_.cols); + throw std::runtime_error(msg); + } + // std::cout << "_dictionary_id: " << _dictionary_id << std::endl; + // Ptr dictionary = aruco::getPredefinedDictionary(aruco::PredefinedDictionaryType(_dictionary_id)); + if (this->_dictionary == nullptr) + { + this->_dictionary = new aruco::Dictionary; + *(this->_dictionary) = aruco::getPredefinedDictionary(aruco::PredefinedDictionaryType(_dictionary_id)); + } + + std::vector ids, ids_final; + std::vector> corners, corners_final, rejected; + std::vector rvecs, tvecs; + + // detect markers and estimate pose + aruco::detectMarkers(img_, this->_dictionary, corners, ids, _detector_params, rejected); + + if (ids.size() > 0) + { + if (_ids_need[0] == -1) { - need = true; + // std::cout << this->camera_matrix << std::endl; + aruco::estimatePoseSingleMarkers(corners, _lengths_need[0], this->camera_matrix, this->distortion, rvecs, tvecs); + ids_final = ids; + corners_final = corners; + } + else + { + for (int i = 0; i < _ids_need.size(); i++) + { + int id_need = _ids_need[i]; + double length_need = _lengths_need[i]; + std::vector t_rvecs, t_tvecs; + std::vector> t_corners; + for (int j = 0; j < ids.size(); j++) + { + if (ids[j] == id_need) + { + t_corners.push_back(corners[j]); + ids_final.push_back(ids[j]); + corners_final.push_back(corners[j]); + } + } + if (t_corners.size() > 0) + { + aruco::estimatePoseSingleMarkers(t_corners, length_need, this->camera_matrix, this->distortion, t_rvecs, t_tvecs); + for (auto t_rvec : t_rvecs) + rvecs.push_back(t_rvec); + for (auto t_tvec : t_tvecs) + tvecs.push_back(t_tvec); + } + } } } - if (!need) label = 0; - yaed::Ellipse e = ellsCned[i]; - if (label > 0) - { - Target tgt; - tgt.setEllipse(e.xc_, e.yc_, e.a_, e.b_, e.rad_, e.score_, tgts_.width, tgts_.height, this->camera_matrix, this->_radius_in_meter); - tgt.setCategory(s_label2str[label], label); - tgts_.targets.push_back(tgt); - } - } - - tgts_.type = MissionType::LANDMARK_DET; -} -bool LandingMarkerDetectorBase::setupImpl() -{ - return false; -} -void LandingMarkerDetectorBase::roiCNN(std::vector& input_rois_, std::vector& output_labels_) -{ - -} - - -void LandingMarkerDetectorBase::_loadLabels() -{ - JsonValue all_value; - JsonAllocator allocator; - _load_all_json(this->alg_params_fn, all_value, allocator); - - JsonValue landing_params_value; - _parser_algorithm_params("LandingMarkerDetector", all_value, landing_params_value); - - for (auto i : landing_params_value) { - if ("labels" == std::string(i->key) && i->value.getTag() == JSON_ARRAY) { - for (auto j : i->value) { - this->_labels_need.push_back(j->value.toString()); - } - } - else if ("maxCandidates" == std::string(i->key)) { - this->_max_candidates = i->value.toNumber(); - // std::cout << "maxCandidates: " << this->_max_candidates << std::endl; - } - } - setupImpl(); -} - - -void EllipseDetector::detectAllInDirectory(std::string input_img_dir_, std::string output_json_dir_) -{ - if (!_params_loaded) - { - this->_load(); - _params_loaded = true; - } - - std::vector files; - yaed::_list_dir(input_img_dir_, files, "jpg"); - - for (size_t i=0; i 9 && files[i].substr(8, 1) == "_") - { - label_str = files[i].substr(9, 1); - std::cout << label_str << std::endl; - } - - cv::Mat resultImage = img.clone(); - - float fMaxCenterDistance = sqrt(float(img.cols*img.cols + img.rows*img.rows)) * this->_max_center_distance_ratio; - _ed->SetMCD(fMaxCenterDistance); - std::vector ellsCned; - _ed->Detect(img, ellsCned); - - std::ofstream ofs(output_json_dir_ + "/" + files[i] + ".json"); - std::string inst_str = ""; - int j = 0; - char buf[1024*32]; - for (yaed::Ellipse e : ellsCned) - { - cv::Rect rect; - e.GetRectangle(rect); - cv::rectangle(resultImage, rect, (0,0,255), 1); - - sprintf(buf, "{\"category_name\":\"%s\",\"bbox\":[%d,%d,%d,%d],\"area\":%d,\"score\":%.3f}", label_str.c_str(), rect.x, rect.y, rect.width, rect.height, rect.width*rect.height, e.score_); - inst_str += std::string(buf); - if (j < ellsCned.size() - 1) - inst_str += ","; - // ofs << e.xc_ << "," << e.yc_ << "," << e.a_ << "," << e.b_ << "," << e.rad_ << "," << e.score_ << std::endl; - j++; - } - - sprintf(buf, "{\"file_name\":\"%s\",\"height\":%d,\"width\":%d,\"annos\":[%s]}", files[i].c_str(), img.rows, img.cols, inst_str.c_str()); - ofs << buf << std::endl; - ofs.close(); - - cv::imshow("img", resultImage); - cv::waitKey(100); - } -} - -void EllipseDetector::_load() -{ - JsonValue all_value; - JsonAllocator allocator; - _load_all_json(this->alg_params_fn, all_value, allocator); - - JsonValue ell_params_value; - _parser_algorithm_params("EllipseDetector", all_value, ell_params_value); - - cv::Size szPreProcessingGaussKernel; - double dPreProcessingGaussSigma; - float fThPosition; - float fMaxCenterDistance; - int iMinEdgeLength; - float fMinOrientedRectSide; - float fDistanceToEllipseContour; - float fMinScore; - float fMinReliability; - int iNs; - double dPercentNe; - float fT_CNC; - float fT_TCN_L; - float fT_TCN_P; - float fThre_R; - - for (auto i : ell_params_value) { - if ("preProcessingGaussKernel" == std::string(i->key)) { - int sigma = i->value.toNumber(); - szPreProcessingGaussKernel = cv::Size(sigma, sigma); - // std::cout << "preProcessingGaussKernel: " << sigma << std::endl; - } - else if ("preProcessingGaussSigma" == std::string(i->key)) { - dPreProcessingGaussSigma = i->value.toNumber(); - // std::cout << "preProcessingGaussSigma: " << dPreProcessingGaussSigma << std::endl; - } - else if ("thPosition" == std::string(i->key)) { - fThPosition = i->value.toNumber(); - // std::cout << "thPosition: " << fThPosition << std::endl; - } - else if ("maxCenterDistance" == std::string(i->key)) { - this->_max_center_distance_ratio = i->value.toNumber(); - fMaxCenterDistance = sqrt(float(this->image_width*this->image_width + this->image_height*this->image_height)) * this->_max_center_distance_ratio; - // std::cout << "maxCenterDistance: " << this->_max_center_distance_ratio << std::endl; - } - else if ("minEdgeLength" == std::string(i->key)) { - iMinEdgeLength = i->value.toNumber(); - // std::cout << "minEdgeLength: " << iMinEdgeLength << std::endl; - } - else if ("minOrientedRectSide" == std::string(i->key)) { - fMinOrientedRectSide = i->value.toNumber(); - // std::cout << "minOrientedRectSide: " << fMinOrientedRectSide << std::endl; - } - else if ("distanceToEllipseContour" == std::string(i->key)) { - fDistanceToEllipseContour = i->value.toNumber(); - // std::cout << "distanceToEllipseContour: " << fDistanceToEllipseContour << std::endl; - } - else if ("minScore" == std::string(i->key)) { - fMinScore = i->value.toNumber(); - // std::cout << "minScore: " << fMinScore << std::endl; - } - else if ("minReliability" == std::string(i->key)) { - fMinReliability = i->value.toNumber(); - // std::cout << "minReliability: " << fMinReliability << std::endl; - } - else if ("ns" == std::string(i->key)) { - iNs = i->value.toNumber(); - // std::cout << "ns: " << iNs << std::endl; - } - else if ("percentNe" == std::string(i->key)) { - dPercentNe = i->value.toNumber(); - // std::cout << "percentNe: " << dPercentNe << std::endl; - } - else if ("T_CNC" == std::string(i->key)) { - fT_CNC = i->value.toNumber(); - // std::cout << "T_CNC: " << fT_CNC << std::endl; - } - else if ("T_TCN_L" == std::string(i->key)) { - fT_TCN_L = i->value.toNumber(); - // std::cout << "T_TCN_L: " << fT_TCN_L << std::endl; - } - else if ("T_TCN_P" == std::string(i->key)) { - fT_TCN_P = i->value.toNumber(); - // std::cout << "T_TCN_P: " << fT_TCN_P << std::endl; - } - else if ("thRadius" == std::string(i->key)) { - fThre_R = i->value.toNumber(); - // std::cout << "thRadius: " << fThre_R << std::endl; - } - else if ("radiusInMeter" == std::string(i->key)) { - this->_radius_in_meter = i->value.toNumber(); - // std::cout << "radiusInMeter: " << this->_radius_in_meter << std::endl; - } - } - - if (_ed) { delete _ed; _ed = NULL; } - _ed = new yaed::EllipseDetector; - _ed->SetParameters(szPreProcessingGaussKernel, dPreProcessingGaussSigma, fThPosition, fMaxCenterDistance, iMinEdgeLength, fMinOrientedRectSide, fDistanceToEllipseContour, fMinScore, fMinReliability, iNs, dPercentNe, fT_CNC, fT_TCN_L, fT_TCN_P, fThre_R); -} - - -SingleObjectTrackerBase::SingleObjectTrackerBase() -{ - this->_params_loaded = false; -} -SingleObjectTrackerBase::~SingleObjectTrackerBase() -{ - -} -bool SingleObjectTrackerBase::isParamsLoaded() -{ - return this->_params_loaded; -} -std::string SingleObjectTrackerBase::getAlgorithm() -{ - return this->_algorithm; -} -int SingleObjectTrackerBase::getBackend() -{ - return this->_backend; -} -int SingleObjectTrackerBase::getTarget() -{ - return this->_target; -} - -void SingleObjectTrackerBase::warmUp() -{ - cv::Mat testim = cv::Mat::zeros(640, 480, CV_8UC3); - this->init(testim, cv::Rect(10, 10, 100, 100)); - TargetsInFrame testtgts(0); - this->track(testim, testtgts); -} -void SingleObjectTrackerBase::init(cv::Mat img_, const cv::Rect& bounding_box_) -{ - if (!this->_params_loaded) - { - this->_load(); - this->_params_loaded = true; - } - - if (bounding_box_.width < 4 || bounding_box_.height < 4) - { - throw std::runtime_error("SpireCV (106) Tracking box size < (4, 4), too small!"); - } - if (bounding_box_.x < 0 || bounding_box_.y < 0 || bounding_box_.x + bounding_box_.width > img_.cols || bounding_box_.y + bounding_box_.height > img_.rows) - { - throw std::runtime_error("SpireCV (106) Tracking box not in the Input Image!"); - } - - initImpl(img_, bounding_box_); -} -void SingleObjectTrackerBase::track(cv::Mat img_, TargetsInFrame& tgts_) -{ - Rect rect; - bool ok = trackImpl(img_, rect); - - tgts_.setSize(img_.cols, img_.rows); - tgts_.setFOV(this->fov_x, this->fov_y); - auto t1 = std::chrono::system_clock::now(); - tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); - this->_t0 = std::chrono::system_clock::now(); - tgts_.setTimeNow(); - - if (ok) - { - Target tgt; - tgt.setBox(rect.x, rect.y, rect.x+rect.width, rect.y+rect.height, img_.cols, img_.rows); - tgt.setTrackID(1); - tgt.setLOS(tgt.cx, tgt.cy, this->camera_matrix, img_.cols, img_.rows); - tgts_.targets.push_back(tgt); - } - - tgts_.type = MissionType::TRACKING; -} -bool SingleObjectTrackerBase::setupImpl() -{ - return false; -} -void SingleObjectTrackerBase::initImpl(cv::Mat img_, const cv::Rect& bounding_box_) -{ - -} -bool SingleObjectTrackerBase::trackImpl(cv::Mat img_, cv::Rect& output_bbox_) -{ - return false; -} -void SingleObjectTrackerBase::_load() -{ - JsonValue all_value; - JsonAllocator allocator; - _load_all_json(this->alg_params_fn, all_value, allocator); - - JsonValue tracker_params_value; - _parser_algorithm_params("SingleObjectTracker", all_value, tracker_params_value); - - for (auto i : tracker_params_value) { - if ("algorithm" == std::string(i->key)) { - this->_algorithm = i->value.toString(); - std::cout << "algorithm: " << this->_algorithm << std::endl; - } - else if ("backend" == std::string(i->key)) { - this->_backend = i->value.toNumber(); - } - else if ("target" == std::string(i->key)) { - this->_target = i->value.toNumber(); - } - } - - setupImpl(); -} - - -CommonObjectDetectorBase::CommonObjectDetectorBase() // : CameraAlgorithm() -{ - this->_params_loaded = false; - // std::cout << "CommonObjectDetectorBase->_params_loaded: " << this->_params_loaded << std::endl; -} -CommonObjectDetectorBase::~CommonObjectDetectorBase() -{ - -} - -bool CommonObjectDetectorBase::isParamsLoaded() -{ - return this->_params_loaded; -} -std::string CommonObjectDetectorBase::getDataset() -{ - return this->_dataset; -} -std::vector CommonObjectDetectorBase::getClassNames() -{ - return this->_class_names; -} -std::vector CommonObjectDetectorBase::getClassWs() -{ - return this->_class_ws; -} -std::vector CommonObjectDetectorBase::getClassHs() -{ - return this->_class_hs; -} -int CommonObjectDetectorBase::getInputH() -{ - return this->_input_h; -} -int CommonObjectDetectorBase::getInputW() -{ - return this->_input_w; -} -int CommonObjectDetectorBase::getClassNum() -{ - return this->_n_classes; -} -int CommonObjectDetectorBase::getOutputSize() -{ - return this->_output_size; -} -double CommonObjectDetectorBase::getThrsNms() -{ - return this->_thrs_nms; -} -double CommonObjectDetectorBase::getThrsConf() -{ - return this->_thrs_conf; -} -int CommonObjectDetectorBase::useWidthOrHeight() -{ - return this->_use_width_or_height; -} -bool CommonObjectDetectorBase::withSegmentation() -{ - return this->_with_segmentation; -} -void CommonObjectDetectorBase::setInputH(int h_) -{ - this->_input_h = h_; -} -void CommonObjectDetectorBase::setInputW(int w_) -{ - this->_input_w = w_; -} - -void CommonObjectDetectorBase::warmUp() -{ - cv::Mat testim = cv::Mat::zeros(640, 480, CV_8UC3); - TargetsInFrame testtgts(0); - this->detect(testim, testtgts); -} - -void CommonObjectDetectorBase::detect(cv::Mat img_, TargetsInFrame& tgts_, Box* roi_, int img_w_, int img_h_) -{ - if (!this->_params_loaded) - { - this->_load(); - this->_params_loaded = true; - } - - if (nullptr != roi_ && img_w_ > 0 && img_h_ > 0) - tgts_.setSize(img_w_, img_h_); - else + // aruco::drawDetectedMarkers(img_, corners_final, ids_final); tgts_.setSize(img_.cols, img_.rows); - tgts_.setFOV(this->fov_x, this->fov_y); - auto t1 = std::chrono::system_clock::now(); - tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); - this->_t0 = std::chrono::system_clock::now(); - tgts_.setTimeNow(); + // tgts_.fov_x = this->fov_x; + // tgts_.fov_y = this->fov_y; + tgts_.setFOV(this->fov_x, this->fov_y); + auto t1 = std::chrono::system_clock::now(); + tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); + this->_t0 = std::chrono::system_clock::now(); + tgts_.setTimeNow(); - std::vector boxes_x; - std::vector boxes_y; - std::vector boxes_w; - std::vector boxes_h; - std::vector boxes_label; - std::vector boxes_score; - std::vector boxes_seg; - detectImpl(img_, boxes_x, boxes_y, boxes_w, boxes_h, boxes_label, boxes_score, boxes_seg); + if (ids_final.size() > 0) + { + for (int i = 0; i < ids_final.size(); i++) + { + Target tgt; + tgt.setAruco(ids_final[i], corners_final[i], rvecs[i], tvecs[i], tgts_.width, tgts_.height, this->camera_matrix); + tgts_.targets.push_back(tgt); - size_t n_objs = boxes_x.size(); - if (n_objs != boxes_y.size() || n_objs != boxes_w.size() || n_objs != boxes_h.size() || n_objs != boxes_label.size() || n_objs != boxes_score.size()) - throw std::runtime_error("SpireCV (106) Error in detectImpl(), Vector Size Not Equal!"); + // Box b; + // tgt.getBox(b); + // cv::circle(img_, cv::Point(int(corners_final[i][0].x), int(corners_final[i][0].y)), 5, cv::Scalar(0,0,255), 2); + // cv::circle(img_, cv::Point(int(corners_final[i][1].x), int(corners_final[i][1].y)), 5, cv::Scalar(255,0,0), 2); + // cv::rectangle(img_, cv::Rect(b.x1, b.y1, b.x2-b.x1+1, b.y2-b.y1+1), cv::Scalar(0,0,255), 1, 1, 0); + } + } - if (this->_with_segmentation && n_objs != boxes_seg.size()) - throw std::runtime_error("SpireCV (106) Error in detectImpl(), Vector Size Not Equal!"); - - for (int j=0; j= img_.cols) ow = img_.cols - ox - 1; - if (oy + oh >= img_.rows) oh = img_.rows - oy - 1; - if (ow > 5 && oh > 5) + this->_ed = NULL; + this->_max_center_distance_ratio = 0.05f; + this->_params_loaded = false; + } + EllipseDetector::~EllipseDetector() + { + if (_ed) + { + delete _ed; + _ed = NULL; + } + } + + void EllipseDetector::detect(cv::Mat img_, TargetsInFrame &tgts_) + { + if (!_params_loaded) + { + this->_load(); + _params_loaded = true; + } + + float fMaxCenterDistance = sqrt(float(img_.cols * img_.cols + img_.rows * img_.rows)) * this->_max_center_distance_ratio; + _ed->SetMCD(fMaxCenterDistance); + std::vector ellsCned; + _ed->Detect(img_, ellsCned); + + tgts_.setSize(img_.cols, img_.rows); + tgts_.setFOV(this->fov_x, this->fov_y); + auto t1 = std::chrono::system_clock::now(); + tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); + this->_t0 = std::chrono::system_clock::now(); + tgts_.setTimeNow(); + + for (yaed::Ellipse ell : ellsCned) { Target tgt; - if (nullptr != roi_ && img_w_ > 0 && img_h_ > 0) - tgt.setBox(roi_->x1 + ox, roi_->y1 + oy, roi_->x1 + ox + ow, roi_->y1 + oy + oh, img_w_, img_h_); - else - tgt.setBox(ox, oy, ox+ow, oy+oh, img_.cols, img_.rows); + tgt.setEllipse(ell.xc_, ell.yc_, ell.a_, ell.b_, ell.rad_, ell.score_, tgts_.width, tgts_.height, this->camera_matrix, this->_radius_in_meter); + tgts_.targets.push_back(tgt); + } + + tgts_.type = MissionType::ELLIPSE_DET; + } + + LandingMarkerDetectorBase::LandingMarkerDetectorBase() + { + // this->_params_loaded = false; + // std::string params_fn = _get_home() + SV_ROOT_DIR + "sv_algorithm_params.json"; + // if (_is_file_exist(params_fn)) + // this->loadAlgorithmParams(params_fn); + setupImpl(); + } + + LandingMarkerDetectorBase::~LandingMarkerDetectorBase() + { + } + + bool LandingMarkerDetectorBase::isParamsLoaded() + { + return this->_params_loaded; + } + int LandingMarkerDetectorBase::getMaxCandidates() + { + return this->_max_candidates; + } + std::vector LandingMarkerDetectorBase::getLabelsNeed() + { + return this->_labels_need; + } + + void LandingMarkerDetectorBase::detect(cv::Mat img_, TargetsInFrame &tgts_) + { + if (!_params_loaded) + { + this->_load(); + this->_loadLabels(); + _params_loaded = true; + } + + float fMaxCenterDistance = sqrt(float(img_.cols * img_.cols + img_.rows * img_.rows)) * this->_max_center_distance_ratio; + _ed->SetMCD(fMaxCenterDistance); + std::vector ellsCned; + _ed->Detect(img_, ellsCned); + + tgts_.setSize(img_.cols, img_.rows); + tgts_.setFOV(this->fov_x, this->fov_y); + auto t1 = std::chrono::system_clock::now(); + tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); + this->_t0 = std::chrono::system_clock::now(); + tgts_.setTimeNow(); + + static std::vector s_label2str = {"neg", "h", "x", "1", "2", "3", "4", "5", "6", "7", "8"}; + int cand_cnt = 0; + std::vector input_rois; + while (cand_cnt < this->_max_candidates && ellsCned.size() > cand_cnt) + { + yaed::Ellipse e = ellsCned[cand_cnt++]; + + cv::Rect rect; + e.GetRectangle(rect); + int x1 = rect.x; + int y1 = rect.y; + int x2 = rect.x + rect.width; + int y2 = rect.y + rect.height; + if (x1 < 0) + x1 = 0; + if (y1 < 0) + y1 = 0; + if (x2 > img_.cols - 1) + x2 = img_.cols - 1; + if (y2 > img_.rows - 1) + y2 = img_.rows - 1; + if (x2 - x1 < 5 || y2 - y1 < 5) + continue; + rect.x = x1; + rect.y = y1; + rect.width = x2 - x1; + rect.height = y2 - y1; + + cv::Mat e_roi = img_(rect); + cv::resize(e_roi, e_roi, cv::Size(32, 32)); + + input_rois.push_back(e_roi); + } + + std::vector output_labels; + roiCNN(input_rois, output_labels); + if (input_rois.size() != output_labels.size()) + throw std::runtime_error("SpireCV (106) input_rois.size() != output_labels.size()"); + + for (int i = 0; i < output_labels.size(); i++) + { + int label = output_labels[i]; + bool need = false; + for (int j = 0; j < _labels_need.size(); j++) + { + if (this->_labels_need[j] == s_label2str[label]) + { + need = true; + } + } + if (!need) + label = 0; + + yaed::Ellipse e = ellsCned[i]; + if (label > 0) + { + Target tgt; + tgt.setEllipse(e.xc_, e.yc_, e.a_, e.b_, e.rad_, e.score_, tgts_.width, tgts_.height, this->camera_matrix, this->_radius_in_meter); + tgt.setCategory(s_label2str[label], label); + tgts_.targets.push_back(tgt); + } + } + + tgts_.type = MissionType::LANDMARK_DET; + } + bool LandingMarkerDetectorBase::setupImpl() + { + return false; + } + void LandingMarkerDetectorBase::roiCNN(std::vector &input_rois_, std::vector &output_labels_) + { + } + + void LandingMarkerDetectorBase::_loadLabels() + { + JsonValue all_value; + JsonAllocator allocator; + _load_all_json(this->alg_params_fn, all_value, allocator); + + JsonValue landing_params_value; + _parser_algorithm_params("LandingMarkerDetector", all_value, landing_params_value); + + for (auto i : landing_params_value) + { + if ("labels" == std::string(i->key) && i->value.getTag() == JSON_ARRAY) + { + for (auto j : i->value) + { + this->_labels_need.push_back(j->value.toString()); + } + } + else if ("maxCandidates" == std::string(i->key)) + { + this->_max_candidates = i->value.toNumber(); + // std::cout << "maxCandidates: " << this->_max_candidates << std::endl; + } + } + setupImpl(); + } + + void EllipseDetector::detectAllInDirectory(std::string input_img_dir_, std::string output_json_dir_) + { + if (!_params_loaded) + { + this->_load(); + _params_loaded = true; + } + + std::vector files; + yaed::_list_dir(input_img_dir_, files, "jpg"); + + for (size_t i = 0; i < files.size(); i++) + { + std::string fn = input_img_dir_ + "/" + files[i]; + cv::Mat img = cv::imread(fn); + std::cout << fn << std::endl; + std::string label_str = "ellipse"; + + if (files[i].size() > 9 && files[i].substr(8, 1) == "_") + { + label_str = files[i].substr(9, 1); + std::cout << label_str << std::endl; + } + + cv::Mat resultImage = img.clone(); + + float fMaxCenterDistance = sqrt(float(img.cols * img.cols + img.rows * img.rows)) * this->_max_center_distance_ratio; + _ed->SetMCD(fMaxCenterDistance); + std::vector ellsCned; + _ed->Detect(img, ellsCned); + + std::ofstream ofs(output_json_dir_ + "/" + files[i] + ".json"); + std::string inst_str = ""; + int j = 0; + char buf[1024 * 32]; + for (yaed::Ellipse e : ellsCned) + { + cv::Rect rect; + e.GetRectangle(rect); + cv::rectangle(resultImage, rect, (0, 0, 255), 1); + + sprintf(buf, "{\"category_name\":\"%s\",\"bbox\":[%d,%d,%d,%d],\"area\":%d,\"score\":%.3f}", label_str.c_str(), rect.x, rect.y, rect.width, rect.height, rect.width * rect.height, e.score_); + inst_str += std::string(buf); + if (j < ellsCned.size() - 1) + inst_str += ","; + // ofs << e.xc_ << "," << e.yc_ << "," << e.a_ << "," << e.b_ << "," << e.rad_ << "," << e.score_ << std::endl; + j++; + } + + sprintf(buf, "{\"file_name\":\"%s\",\"height\":%d,\"width\":%d,\"annos\":[%s]}", files[i].c_str(), img.rows, img.cols, inst_str.c_str()); + ofs << buf << std::endl; + ofs.close(); + + cv::imshow("img", resultImage); + cv::waitKey(100); + } + } + + void EllipseDetector::_load() + { + JsonValue all_value; + JsonAllocator allocator; + _load_all_json(this->alg_params_fn, all_value, allocator); + + JsonValue ell_params_value; + _parser_algorithm_params("EllipseDetector", all_value, ell_params_value); + + cv::Size szPreProcessingGaussKernel; + double dPreProcessingGaussSigma; + float fThPosition; + float fMaxCenterDistance; + int iMinEdgeLength; + float fMinOrientedRectSide; + float fDistanceToEllipseContour; + float fMinScore; + float fMinReliability; + int iNs; + double dPercentNe; + float fT_CNC; + float fT_TCN_L; + float fT_TCN_P; + float fThre_R; + + for (auto i : ell_params_value) + { + if ("preProcessingGaussKernel" == std::string(i->key)) + { + int sigma = i->value.toNumber(); + szPreProcessingGaussKernel = cv::Size(sigma, sigma); + // std::cout << "preProcessingGaussKernel: " << sigma << std::endl; + } + else if ("preProcessingGaussSigma" == std::string(i->key)) + { + dPreProcessingGaussSigma = i->value.toNumber(); + // std::cout << "preProcessingGaussSigma: " << dPreProcessingGaussSigma << std::endl; + } + else if ("thPosition" == std::string(i->key)) + { + fThPosition = i->value.toNumber(); + // std::cout << "thPosition: " << fThPosition << std::endl; + } + else if ("maxCenterDistance" == std::string(i->key)) + { + this->_max_center_distance_ratio = i->value.toNumber(); + fMaxCenterDistance = sqrt(float(this->image_width * this->image_width + this->image_height * this->image_height)) * this->_max_center_distance_ratio; + // std::cout << "maxCenterDistance: " << this->_max_center_distance_ratio << std::endl; + } + else if ("minEdgeLength" == std::string(i->key)) + { + iMinEdgeLength = i->value.toNumber(); + // std::cout << "minEdgeLength: " << iMinEdgeLength << std::endl; + } + else if ("minOrientedRectSide" == std::string(i->key)) + { + fMinOrientedRectSide = i->value.toNumber(); + // std::cout << "minOrientedRectSide: " << fMinOrientedRectSide << std::endl; + } + else if ("distanceToEllipseContour" == std::string(i->key)) + { + fDistanceToEllipseContour = i->value.toNumber(); + // std::cout << "distanceToEllipseContour: " << fDistanceToEllipseContour << std::endl; + } + else if ("minScore" == std::string(i->key)) + { + fMinScore = i->value.toNumber(); + // std::cout << "minScore: " << fMinScore << std::endl; + } + else if ("minReliability" == std::string(i->key)) + { + fMinReliability = i->value.toNumber(); + // std::cout << "minReliability: " << fMinReliability << std::endl; + } + else if ("ns" == std::string(i->key)) + { + iNs = i->value.toNumber(); + // std::cout << "ns: " << iNs << std::endl; + } + else if ("percentNe" == std::string(i->key)) + { + dPercentNe = i->value.toNumber(); + // std::cout << "percentNe: " << dPercentNe << std::endl; + } + else if ("T_CNC" == std::string(i->key)) + { + fT_CNC = i->value.toNumber(); + // std::cout << "T_CNC: " << fT_CNC << std::endl; + } + else if ("T_TCN_L" == std::string(i->key)) + { + fT_TCN_L = i->value.toNumber(); + // std::cout << "T_TCN_L: " << fT_TCN_L << std::endl; + } + else if ("T_TCN_P" == std::string(i->key)) + { + fT_TCN_P = i->value.toNumber(); + // std::cout << "T_TCN_P: " << fT_TCN_P << std::endl; + } + else if ("thRadius" == std::string(i->key)) + { + fThre_R = i->value.toNumber(); + // std::cout << "thRadius: " << fThre_R << std::endl; + } + else if ("radiusInMeter" == std::string(i->key)) + { + this->_radius_in_meter = i->value.toNumber(); + // std::cout << "radiusInMeter: " << this->_radius_in_meter << std::endl; + } + } + + if (_ed) + { + delete _ed; + _ed = NULL; + } + _ed = new yaed::EllipseDetector; + _ed->SetParameters(szPreProcessingGaussKernel, dPreProcessingGaussSigma, fThPosition, fMaxCenterDistance, iMinEdgeLength, fMinOrientedRectSide, fDistanceToEllipseContour, fMinScore, fMinReliability, iNs, dPercentNe, fT_CNC, fT_TCN_L, fT_TCN_P, fThre_R); + } + + SingleObjectTrackerBase::SingleObjectTrackerBase() + { + this->_params_loaded = false; + } + SingleObjectTrackerBase::~SingleObjectTrackerBase() + { + } + bool SingleObjectTrackerBase::isParamsLoaded() + { + return this->_params_loaded; + } + std::string SingleObjectTrackerBase::getAlgorithm() + { + return this->_algorithm; + } + int SingleObjectTrackerBase::getBackend() + { + return this->_backend; + } + int SingleObjectTrackerBase::getTarget() + { + return this->_target; + } + double SingleObjectTrackerBase::getObjectWs() + { + return this->_object_ws; + } + double SingleObjectTrackerBase::getObjectHs() + { + return this->_object_hs; + } + int SingleObjectTrackerBase::useWidthOrHeight() + { + return this->_use_width_or_height; + } + + void SingleObjectTrackerBase::warmUp() + { + cv::Mat testim = cv::Mat::zeros(640, 480, CV_8UC3); + this->init(testim, cv::Rect(10, 10, 100, 100)); + TargetsInFrame testtgts(0); + this->track(testim, testtgts); + } + void SingleObjectTrackerBase::init(cv::Mat img_, const cv::Rect &bounding_box_) + { + if (!this->_params_loaded) + { + this->_load(); + this->_params_loaded = true; + } + + if (bounding_box_.width < 4 || bounding_box_.height < 4) + { + throw std::runtime_error("SpireCV (106) Tracking box size < (4, 4), too small!"); + } + if (bounding_box_.x < 0 || bounding_box_.y < 0 || bounding_box_.x + bounding_box_.width > img_.cols || bounding_box_.y + bounding_box_.height > img_.rows) + { + throw std::runtime_error("SpireCV (106) Tracking box not in the Input Image!"); + } + + initImpl(img_, bounding_box_); + } + void SingleObjectTrackerBase::track(cv::Mat img_, TargetsInFrame &tgts_) + { + Rect rect; + bool ok = trackImpl(img_, rect); + + tgts_.setSize(img_.cols, img_.rows); + tgts_.setFOV(this->fov_x, this->fov_y); + auto t1 = std::chrono::system_clock::now(); + tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); + this->_t0 = std::chrono::system_clock::now(); + tgts_.setTimeNow(); + + if (ok) + { + Target tgt; + tgt.setBox(rect.x, rect.y, rect.x + rect.width, rect.y + rect.height, img_.cols, img_.rows); + tgt.setTrackID(1); + tgt.setLOS(tgt.cx, tgt.cy, this->camera_matrix, img_.cols, img_.rows); + int ow = int(round(rect.width)); + int oh = int(round(rect.height)); - int cat_id = boxes_label[j]; - tgt.setCategory(this->_class_names[cat_id], cat_id); - if (nullptr != roi_ && img_w_ > 0 && img_h_ > 0) - tgt.setLOS(tgt.cx, tgt.cy, this->camera_matrix, img_w_, img_h_); - else - tgt.setLOS(tgt.cx, tgt.cy, this->camera_matrix, img_.cols, img_.rows); - tgt.score = boxes_score[j]; if (this->_use_width_or_height == 0) { - double z = this->camera_matrix.at(0, 0) * this->_class_ws[cat_id] / ow; + double z = this->camera_matrix.at(0, 0) * this->_object_ws / ow; double x = tan(tgt.los_ax / SV_RAD2DEG) * z; double y = tan(tgt.los_ay / SV_RAD2DEG) * z; tgt.setPosition(x, y, z); } else if (this->_use_width_or_height == 1) { - double z = this->camera_matrix.at(1, 1) * this->_class_hs[cat_id] / oh; + double z = this->camera_matrix.at(1, 1) * this->_object_hs / oh; double x = tan(tgt.los_ax / SV_RAD2DEG) * z; double y = tan(tgt.los_ay / SV_RAD2DEG) * z; tgt.setPosition(x, y, z); } - if (this->_with_segmentation) - { - cv::Mat mask_j = boxes_seg[j].clone(); - int maskh = mask_j.rows, maskw = mask_j.cols; - assert(maskh == maskw); - - if (img_.cols > img_.rows) - { - int cut_h = (int)round((img_.rows * 1. / img_.cols) * maskh); - int gap_h = (int)round((maskh - cut_h) / 2.); - mask_j = mask_j.rowRange(gap_h, gap_h + cut_h); - } - else if (img_.cols < img_.rows) - { - int cut_w = (int)round((img_.cols * 1. / img_.rows) * maskh); - int gap_w = (int)round((maskh - cut_w) / 2.); - mask_j = mask_j.colRange(gap_w, gap_w + cut_w); - } - - if (nullptr != roi_ && img_w_ > 0 && img_h_ > 0) - { - cv::resize(mask_j, mask_j, cv::Size(img_.cols, img_.rows)); - - cv::Mat mask_out = cv::Mat::zeros(img_h_, img_w_, CV_32FC1); - mask_j.copyTo(mask_out(cv::Rect(roi_->x1, roi_->y1, mask_j.cols, mask_j.rows))); - - tgt.setMask(mask_out); - } - else - { - tgt.setMask(mask_j); - } - } - tgts_.targets.push_back(tgt); } + + tgts_.type = MissionType::TRACKING; + } + bool SingleObjectTrackerBase::setupImpl() + { + return false; + } + void SingleObjectTrackerBase::initImpl(cv::Mat img_, const cv::Rect &bounding_box_) + { + } + bool SingleObjectTrackerBase::trackImpl(cv::Mat img_, cv::Rect &output_bbox_) + { + return false; + } + void SingleObjectTrackerBase::_load() + { + JsonValue all_value; + JsonAllocator allocator; + _load_all_json(this->alg_params_fn, all_value, allocator); + + JsonValue tracker_params_value; + _parser_algorithm_params("SingleObjectTracker", all_value, tracker_params_value); + + for (auto i : tracker_params_value) + { + if ("algorithm" == std::string(i->key)) + { + this->_algorithm = i->value.toString(); + std::cout << "algorithm: " << this->_algorithm << std::endl; + } + else if ("backend" == std::string(i->key)) + { + this->_backend = i->value.toNumber(); + } + else if ("target" == std::string(i->key)) + { + this->_target = i->value.toNumber(); + } + else if ("useWidthOrHeight" == std::string(i->key)) + { + this->_use_width_or_height = i->value.toNumber(); + } + else if ("sigleobjectW" == std::string(i->key)) + { + this->_object_ws = i->value.toNumber(); + } + else if ("sigleobjectH" == std::string(i->key)) + { + this->_object_hs = i->value.toNumber(); + } + } + + setupImpl(); } - tgts_.type = MissionType::COMMON_DET; -} + CommonObjectDetectorBase::CommonObjectDetectorBase() // : CameraAlgorithm() + { + this->_params_loaded = false; + // std::cout << "CommonObjectDetectorBase->_params_loaded: " << this->_params_loaded << std::endl; + } + CommonObjectDetectorBase::~CommonObjectDetectorBase() + { + } -bool CommonObjectDetectorBase::setupImpl() -{ - return false; -} + bool CommonObjectDetectorBase::isParamsLoaded() + { + return this->_params_loaded; + } + std::string CommonObjectDetectorBase::getDataset() + { + return this->_dataset; + } + std::vector CommonObjectDetectorBase::getClassNames() + { + return this->_class_names; + } + std::vector CommonObjectDetectorBase::getClassWs() + { + return this->_class_ws; + } + std::vector CommonObjectDetectorBase::getClassHs() + { + return this->_class_hs; + } + int CommonObjectDetectorBase::getInputH() + { + return this->_input_h; + } + int CommonObjectDetectorBase::getInputW() + { + return this->_input_w; + } + int CommonObjectDetectorBase::getClassNum() + { + return this->_n_classes; + } + int CommonObjectDetectorBase::getOutputSize() + { + return this->_output_size; + } + double CommonObjectDetectorBase::getThrsNms() + { + return this->_thrs_nms; + } + double CommonObjectDetectorBase::getThrsConf() + { + return this->_thrs_conf; + } + int CommonObjectDetectorBase::useWidthOrHeight() + { + return this->_use_width_or_height; + } + bool CommonObjectDetectorBase::withSegmentation() + { + return this->_with_segmentation; + } + void CommonObjectDetectorBase::setInputH(int h_) + { + this->_input_h = h_; + } + void CommonObjectDetectorBase::setInputW(int w_) + { + this->_input_w = w_; + } -void CommonObjectDetectorBase::detectImpl( - cv::Mat img_, - std::vector& boxes_x_, - std::vector& boxes_y_, - std::vector& boxes_w_, - std::vector& boxes_h_, - std::vector& boxes_label_, - std::vector& boxes_score_, - std::vector& boxes_seg_ -) -{ + void CommonObjectDetectorBase::warmUp() + { + cv::Mat testim = cv::Mat::zeros(640, 480, CV_8UC3); + TargetsInFrame testtgts(0); + this->detect(testim, testtgts); + } -} - -void CommonObjectDetectorBase::_load() -{ - JsonValue all_value; - JsonAllocator allocator; - _load_all_json(this->alg_params_fn, all_value, allocator); - - JsonValue detector_params_value; - _parser_algorithm_params("CommonObjectDetector", all_value, detector_params_value); - - // std::cout << _get_home() + "/.spire/" << std::endl; - // stuff we know about the network and the input/output blobs - this->_input_h = 640; - this->_input_w = 640; - this->_n_classes = 1; - this->_thrs_nms = 0.6; - this->_thrs_conf = 0.4; - this->_use_width_or_height = 0; - - for (auto i : detector_params_value) { - - if ("dataset" == std::string(i->key)) { - this->_dataset = i->value.toString(); - std::cout << "dataset: " << this->_dataset << std::endl; + void CommonObjectDetectorBase::detect(cv::Mat img_, TargetsInFrame &tgts_, Box *roi_, int img_w_, int img_h_) + { + if (!this->_params_loaded) + { + this->_load(); + this->_params_loaded = true; } - 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(); - if (this->_input_w != 640 && this->_input_w != 1280) + + if (nullptr != roi_ && img_w_ > 0 && img_h_ > 0) + tgts_.setSize(img_w_, img_h_); + else + tgts_.setSize(img_.cols, img_.rows); + + tgts_.setFOV(this->fov_x, this->fov_y); + auto t1 = std::chrono::system_clock::now(); + tgts_.setFPS(1000.0 / std::chrono::duration_cast(t1 - this->_t0).count()); + this->_t0 = std::chrono::system_clock::now(); + tgts_.setTimeNow(); + + std::vector boxes_x; + std::vector boxes_y; + std::vector boxes_w; + std::vector boxes_h; + std::vector boxes_label; + std::vector boxes_score; + std::vector boxes_seg; + detectImpl(img_, boxes_x, boxes_y, boxes_w, boxes_h, boxes_label, boxes_score, boxes_seg); + + size_t n_objs = boxes_x.size(); + if (n_objs != boxes_y.size() || n_objs != boxes_w.size() || n_objs != boxes_h.size() || n_objs != boxes_label.size() || n_objs != boxes_score.size()) + throw std::runtime_error("SpireCV (106) Error in detectImpl(), Vector Size Not Equal!"); + + if (this->_with_segmentation && n_objs != boxes_seg.size()) + throw std::runtime_error("SpireCV (106) Error in detectImpl(), Vector Size Not Equal!"); + + for (int j = 0; j < n_objs; j++) + { + int ox = int(round(boxes_x[j])); + int oy = int(round(boxes_y[j])); + int ow = int(round(boxes_w[j])); + int oh = int(round(boxes_h[j])); + if (ox < 0) + ox = 0; + if (oy < 0) + oy = 0; + if (ox + ow >= img_.cols) + ow = img_.cols - ox - 1; + if (oy + oh >= img_.rows) + oh = img_.rows - oy - 1; + if (ow > 5 && oh > 5) { - throw std::runtime_error("SpireCV (106) inputSize should be 640 or 1280!"); - } - this->_input_h = this->_input_w; - } - else if ("nmsThrs" == std::string(i->key)) { - // std::cout << "nmsThrs (old, new): " << this->_thrs_nms << ", " << i->value.toNumber() << std::endl; - this->_thrs_nms = i->value.toNumber(); - } - else if ("scoreThrs" == std::string(i->key)) { - // std::cout << "scoreThrs (old, new): " << this->_thrs_conf << ", " << i->value.toNumber() << std::endl; - this->_thrs_conf = i->value.toNumber(); - } - else if ("useWidthOrHeight" == std::string(i->key)) { - // std::cout << "useWidthOrHeight (old, new): " << this->_use_width_or_height << ", " << i->value.toNumber() << std::endl; - this->_use_width_or_height = i->value.toNumber(); - } - else if ("withSegmentation" == std::string(i->key)) { - bool json_tf = false; - if (i->value.getTag() == JSON_TRUE) json_tf = true; - this->_with_segmentation = json_tf; - } - else if ("dataset" + this->_dataset == std::string(i->key)) { - if (i->value.getTag() == JSON_OBJECT) { - for (auto j : i->value) { - // std::cout << j->key << std::endl; - _class_names.push_back(std::string(j->key)); - if (j->value.getTag() == JSON_ARRAY) + Target tgt; + if (nullptr != roi_ && img_w_ > 0 && img_h_ > 0) + tgt.setBox(roi_->x1 + ox, roi_->y1 + oy, roi_->x1 + ox + ow, roi_->y1 + oy + oh, img_w_, img_h_); + else + tgt.setBox(ox, oy, ox + ow, oy + oh, img_.cols, img_.rows); + + int cat_id = boxes_label[j]; + tgt.setCategory(this->_class_names[cat_id], cat_id); + if (nullptr != roi_ && img_w_ > 0 && img_h_ > 0) + tgt.setLOS(tgt.cx, tgt.cy, this->camera_matrix, img_w_, img_h_); + else + tgt.setLOS(tgt.cx, tgt.cy, this->camera_matrix, img_.cols, img_.rows); + tgt.score = boxes_score[j]; + if (this->_use_width_or_height == 0) + { + double z = this->camera_matrix.at(0, 0) * this->_class_ws[cat_id] / ow; + double x = tan(tgt.los_ax / SV_RAD2DEG) * z; + double y = tan(tgt.los_ay / SV_RAD2DEG) * z; + tgt.setPosition(x, y, z); + } + else if (this->_use_width_or_height == 1) + { + double z = this->camera_matrix.at(1, 1) * this->_class_hs[cat_id] / oh; + double x = tan(tgt.los_ax / SV_RAD2DEG) * z; + double y = tan(tgt.los_ay / SV_RAD2DEG) * z; + tgt.setPosition(x, y, z); + } + + if (this->_with_segmentation) + { + cv::Mat mask_j = boxes_seg[j].clone(); + int maskh = mask_j.rows, maskw = mask_j.cols; + assert(maskh == maskw); + + if (img_.cols > img_.rows) { - int k_cnt = 0; - for (auto k : j->value) { - // std::cout << k->value.toNumber() << std::endl; - if (k_cnt == 0) _class_ws.push_back(k->value.toNumber()); - else if (k_cnt == 1) _class_hs.push_back(k->value.toNumber()); - k_cnt ++; + int cut_h = (int)round((img_.rows * 1. / img_.cols) * maskh); + int gap_h = (int)round((maskh - cut_h) / 2.); + mask_j = mask_j.rowRange(gap_h, gap_h + cut_h); + } + else if (img_.cols < img_.rows) + { + int cut_w = (int)round((img_.cols * 1. / img_.rows) * maskh); + int gap_w = (int)round((maskh - cut_w) / 2.); + mask_j = mask_j.colRange(gap_w, gap_w + cut_w); + } + + if (nullptr != roi_ && img_w_ > 0 && img_h_ > 0) + { + cv::resize(mask_j, mask_j, cv::Size(img_.cols, img_.rows)); + + cv::Mat mask_out = cv::Mat::zeros(img_h_, img_w_, CV_32FC1); + mask_j.copyTo(mask_out(cv::Rect(roi_->x1, roi_->y1, mask_j.cols, mask_j.rows))); + + tgt.setMask(mask_out); + } + else + { + tgt.setMask(mask_j); + } + } + + tgts_.targets.push_back(tgt); + } + } + + tgts_.type = MissionType::COMMON_DET; + } + + bool CommonObjectDetectorBase::setupImpl() + { + return false; + } + + void CommonObjectDetectorBase::detectImpl( + cv::Mat img_, + std::vector &boxes_x_, + std::vector &boxes_y_, + std::vector &boxes_w_, + std::vector &boxes_h_, + std::vector &boxes_label_, + std::vector &boxes_score_, + std::vector &boxes_seg_) + { + } + + void CommonObjectDetectorBase::_load() + { + JsonValue all_value; + JsonAllocator allocator; + _load_all_json(this->alg_params_fn, all_value, allocator); + + JsonValue detector_params_value; + _parser_algorithm_params("CommonObjectDetector", all_value, detector_params_value); + + // std::cout << _get_home() + "/.spire/" << std::endl; + // stuff we know about the network and the input/output blobs + this->_input_h = 640; + this->_input_w = 640; + this->_n_classes = 1; + this->_thrs_nms = 0.6; + this->_thrs_conf = 0.4; + this->_use_width_or_height = 0; + + for (auto i : detector_params_value) + { + + if ("dataset" == std::string(i->key)) + { + this->_dataset = i->value.toString(); + std::cout << "dataset: " << this->_dataset << std::endl; + } + 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(); + if (this->_input_w != 640 && this->_input_w != 1280) + { + throw std::runtime_error("SpireCV (106) inputSize should be 640 or 1280!"); + } + this->_input_h = this->_input_w; + } + else if ("nmsThrs" == std::string(i->key)) + { + // std::cout << "nmsThrs (old, new): " << this->_thrs_nms << ", " << i->value.toNumber() << std::endl; + this->_thrs_nms = i->value.toNumber(); + } + else if ("scoreThrs" == std::string(i->key)) + { + // std::cout << "scoreThrs (old, new): " << this->_thrs_conf << ", " << i->value.toNumber() << std::endl; + this->_thrs_conf = i->value.toNumber(); + } + else if ("useWidthOrHeight" == std::string(i->key)) + { + // std::cout << "useWidthOrHeight (old, new): " << this->_use_width_or_height << ", " << i->value.toNumber() << std::endl; + this->_use_width_or_height = i->value.toNumber(); + } + else if ("withSegmentation" == std::string(i->key)) + { + bool json_tf = false; + if (i->value.getTag() == JSON_TRUE) + json_tf = true; + this->_with_segmentation = json_tf; + } + else if ("dataset" + this->_dataset == std::string(i->key)) + { + if (i->value.getTag() == JSON_OBJECT) + { + for (auto j : i->value) + { + // std::cout << j->key << std::endl; + _class_names.push_back(std::string(j->key)); + if (j->value.getTag() == JSON_ARRAY) + { + int k_cnt = 0; + for (auto k : j->value) + { + // std::cout << k->value.toNumber() << std::endl; + if (k_cnt == 0) + _class_ws.push_back(k->value.toNumber()); + else if (k_cnt == 1) + _class_hs.push_back(k->value.toNumber()); + k_cnt++; + } } } } } } + + setupImpl(); } - setupImpl(); - -} - - - - - - - - - - - - - } diff --git a/build_on_jetson.sh b/build_on_jetson.sh old mode 100755 new mode 100644 diff --git a/build_on_x86_cuda.sh b/build_on_x86_cuda.sh old mode 100755 new mode 100644 diff --git a/build_on_x86_intel.sh b/build_on_x86_intel.sh old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/README.md b/gimbal_ctrl/IOs/serial/README.md old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/include/serial/impl/unix.h b/gimbal_ctrl/IOs/serial/include/serial/impl/unix.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/include/serial/impl/win.h b/gimbal_ctrl/IOs/serial/include/serial/impl/win.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/include/serial/serial.h b/gimbal_ctrl/IOs/serial/include/serial/serial.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/include/serial/v8stdint.h b/gimbal_ctrl/IOs/serial/include/serial/v8stdint.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_linux.cc b/gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_linux.cc old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_osx.cc b/gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_osx.cc old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_win.cc b/gimbal_ctrl/IOs/serial/src/impl/list_ports/list_ports_win.cc old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/src/impl/unix.cc b/gimbal_ctrl/IOs/serial/src/impl/unix.cc old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/src/impl/win.cc b/gimbal_ctrl/IOs/serial/src/impl/win.cc old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/IOs/serial/src/serial.cc b/gimbal_ctrl/IOs/serial/src/serial.cc old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_crc32.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.cpp old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_driver.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_funtion.cpp b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_funtion.cpp old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/AT10/AT10_gimbal_struct.h b/gimbal_ctrl/driver/src/AT10/AT10_gimbal_struct.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/CMakeLists.txt b/gimbal_ctrl/driver/src/CMakeLists.txt old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/FIFO/CMakeLists.txt b/gimbal_ctrl/driver/src/FIFO/CMakeLists.txt old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp b/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.cpp old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h b/gimbal_ctrl/driver/src/FIFO/Ring_Fifo.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h b/gimbal_ctrl/driver/src/G1/g1_gimbal_crc32.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp b/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.cpp old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h b/gimbal_ctrl/driver/src/G1/g1_gimbal_driver.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp b/gimbal_ctrl/driver/src/G1/g1_gimbal_funtion.cpp old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h b/gimbal_ctrl/driver/src/G1/g1_gimbal_struct.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_crc32.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.cpp old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_driver.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_funtion.cpp old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h b/gimbal_ctrl/driver/src/Q10f/Q10f_gimbal_struct.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/amov_gimbal.cpp b/gimbal_ctrl/driver/src/amov_gimbal.cpp old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/amov_gimbal.h b/gimbal_ctrl/driver/src/amov_gimbal.h old mode 100755 new mode 100644 diff --git a/gimbal_ctrl/driver/src/amov_gimbal_struct.h b/gimbal_ctrl/driver/src/amov_gimbal_struct.h old mode 100755 new mode 100644 diff --git a/include/sv_algorithm_base.h b/include/sv_algorithm_base.h index 1e17993..05b6e12 100644 --- a/include/sv_algorithm_base.h +++ b/include/sv_algorithm_base.h @@ -104,6 +104,10 @@ public: std::string getAlgorithm(); int getBackend(); int getTarget(); + double getObjectWs(); + double getObjectHs(); + int useWidthOrHeight(); + protected: virtual bool setupImpl(); virtual void initImpl(cv::Mat img_, const cv::Rect& bounding_box_); @@ -113,6 +117,9 @@ protected: std::string _algorithm; int _backend; int _target; + int _use_width_or_height; + double _object_ws; + double _object_hs; }; @@ -170,3 +177,4 @@ protected: } #endif + diff --git a/include/sv_common_det.h b/include/sv_common_det.h index 30d39ab..1bb14fe 100644 --- a/include/sv_common_det.h +++ b/include/sv_common_det.h @@ -16,7 +16,7 @@ class CommonObjectDetectorCUDAImpl; class CommonObjectDetector : public CommonObjectDetectorBase { public: - CommonObjectDetector(bool input_4k=false); + CommonObjectDetector(); ~CommonObjectDetector(); protected: bool setupImpl(); @@ -32,7 +32,6 @@ protected: ); CommonObjectDetectorCUDAImpl* _cuda_impl; - bool _input_4k; }; diff --git a/include/sv_video_base.h b/include/sv_video_base.h index 18e403e..2731947 100644 --- a/include/sv_video_base.h +++ b/include/sv_video_base.h @@ -12,6 +12,9 @@ #include #include // for sockaddr_in +#include +#include + #define SV_RAD2DEG 57.2957795 // #define X86_PLATFORM // #define JETSON_PLATFORM @@ -358,7 +361,15 @@ protected: void _run(); bool _is_running; + +// new mutex + std::mutex _frame_mutex; + std::condition_variable_any _frame_empty; + +//old flag bool _is_updated; + + std::thread _tt; cv::VideoCapture _cap; cv::Mat _frame; @@ -391,6 +402,8 @@ void drawTargetsInFrame( bool with_yaw=false ); + + void drawTargetsInFrame( cv::Mat& img_, const TargetsInFrame& tgts_, @@ -410,3 +423,4 @@ void list_dir(std::string dir, std::vector& files, std::string suff } #endif + diff --git a/params/a-params/sv_algorithm_params.json b/params/a-params/sv_algorithm_params.json index 6d2bd9d..47ac746 100644 --- a/params/a-params/sv_algorithm_params.json +++ b/params/a-params/sv_algorithm_params.json @@ -1,11 +1,11 @@ { "CommonObjectDetector": { - "dataset": "COCO", + "dataset": "CAR", "inputSize": 640, "nmsThrs": 0.6, - "scoreThrs": 0.4, + "scoreThrs": 0.6, "useWidthOrHeight": 1, - "withSegmentation": true, + "withSegmentation": false, "datasetPersonVehicle": { "person": [0.5, 1.8], "car": [4.1, 1.5], @@ -19,6 +19,9 @@ "datasetDrone": { "drone": [0.4, 0.2] }, + "datasetCAR": { + "car": [0.12, 0.1] + }, "datasetCOCO": { "person": [-1, -1], "bicycle": [-1, -1], @@ -114,7 +117,10 @@ "SingleObjectTracker": { "algorithm": "nano", "backend": 0, - "target": 0 + "target": 0, + "useWidthOrHeight": 0, + "sigleobjectW":0.126, + "sigleobjectH":-1 }, "MultipleObjectTracker": { "algorithm": "sort", @@ -151,7 +157,7 @@ "ArucoDetector": { "dictionaryId": 10, "markerIds": [-1], - "markerLengths": [0.2], + "markerLengths": [0.17], "adaptiveThreshConstant": 7, "adaptiveThreshWinSizeMax": 23, "adaptiveThreshWinSizeMin": 3, diff --git a/samples/calib/calibrate_camera_charuco.cpp b/samples/calib/calibrate_camera_charuco.cpp index 7337dd2..42dd9b6 100644 --- a/samples/calib/calibrate_camera_charuco.cpp +++ b/samples/calib/calibrate_camera_charuco.cpp @@ -124,7 +124,9 @@ int main(int argc, char *argv[]) { inputVideo.open(video); waitTime = 0; } else { - inputVideo.open(camId); + char pipe[512]; + sprintf(pipe, "rtsp://192.168.2.64:554/H264?W=1280&H=720&FPS=30&BR=4000000"); + inputVideo.open(pipe); waitTime = 10; } diff --git a/samples/demo/aruco_detection.cpp b/samples/demo/aruco_detection.cpp index 0229400..9a5ba00 100644 --- a/samples/demo/aruco_detection.cpp +++ b/samples/demo/aruco_detection.cpp @@ -9,13 +9,13 @@ 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/calib_webcam_1280x720.yaml"); // 打开摄像头 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::WEBCAM, 4); // CameraID 0 // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; int frame_id = 0; diff --git a/samples/demo/detection_with_clicked_tracking.cpp b/samples/demo/detection_with_clicked_tracking.cpp index 7cefc72..bf03505 100644 --- a/samples/demo/detection_with_clicked_tracking.cpp +++ b/samples/demo/detection_with_clicked_tracking.cpp @@ -40,18 +40,18 @@ 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"); sv::CommonObjectDetector cod; - cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml"); + cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml"); // 打开摄像头 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::WEBCAM, 4); // CameraID 0 // cv::VideoCapture cap("/home/amov/SpireCV/test/tracking_1280x720.mp4"); // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; diff --git a/samples/demo/ellipse_detection.cpp b/samples/demo/ellipse_detection.cpp index 596bf2f..ccfa02b 100644 --- a/samples/demo/ellipse_detection.cpp +++ b/samples/demo/ellipse_detection.cpp @@ -9,13 +9,13 @@ 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/calib_webcam_1280x720.yaml"); // 打开摄像头 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::WEBCAM, 4); // CameraID 0 // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; int frame_id = 0; diff --git a/samples/demo/gimbal_detection_with_clicked_tracking.cpp b/samples/demo/gimbal_detection_with_clicked_tracking.cpp index c9d1800..0361076 100644 --- a/samples/demo/gimbal_detection_with_clicked_tracking.cpp +++ b/samples/demo/gimbal_detection_with_clicked_tracking.cpp @@ -66,7 +66,7 @@ int main(int argc, char *argv[]) // 设置获取画面分辨率为720P cap.setWH(1280, 720); // 设置视频帧率为30帧 - cap.setFps(30); + cap.setFps(60); // 开启相机 cap.open(sv::CameraType::G1); @@ -77,10 +77,10 @@ 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"); sv::CommonObjectDetector cod; - cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_640x480.yaml"); + cod.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml"); // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; @@ -248,4 +248,4 @@ void GimableCallback(double &frame_ang_r, double &frame_ang_p, double &frame_ang count = 0; } count++; -} \ No newline at end of file +} diff --git a/samples/demo/gimbal_landing_marker_detection.cpp b/samples/demo/gimbal_landing_marker_detection.cpp index f6e0357..60e0aad 100644 --- a/samples/demo/gimbal_landing_marker_detection.cpp +++ b/samples/demo/gimbal_landing_marker_detection.cpp @@ -3,7 +3,7 @@ // 包含SpireCV SDK头文件 #include // #include "gimbal_tools.hpp" - +#include using namespace std; // 云台 @@ -43,11 +43,11 @@ int main(int argc, char *argv[]) // 定义相机 sv::Camera cap; // 设置相机流媒体地址为 192.168.2.64 - cap.setIp("192.168.2.64"); + cap.setIp("192.168.1.64"); // 设置获取画面分辨率为720P - cap.setWH(1280, 720); + cap.setWH(640, 480); // 设置视频帧率为30帧 - cap.setFps(30); + cap.setFps(120); // 开启相机 cap.open(sv::CameraType::G1); @@ -58,56 +58,63 @@ 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/calib_webcam_640x480.yaml"); // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; int frame_id = 0; while (1) { + auto time1 = std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count(); // 实例化SpireCV的 单帧检测结果 接口类 TargetsInFrame + for(uint j = 0; j < 60; j++) + { sv::TargetsInFrame tgts(frame_id++); // 读取一帧图像到img cap.read(img); - cv::resize(img, img, cv::Size(lmd.image_width, lmd.image_height)); + //cv::resize(img, img, cv::Size(lmd.image_width, lmd.image_height)); // 执行 降落标志 检测 lmd.detect(img, tgts); // 可视化检测结果,叠加到img上 - sv::drawTargetsInFrame(img, tgts); + //sv::drawTargetsInFrame(img, tgts); // 控制台打印 降落标志 检测结果 - printf("Frame-[%d]\n", frame_id); + //printf("Frame-[%d]\n", frame_id); // 打印当前检测的FPS printf(" FPS = %.2f\n", tgts.fps); // 打印当前相机的视场角(degree) - printf(" FOV (fx, fy) = (%.2f, %.2f)\n", tgts.fov_x, tgts.fov_y); - for (int i = 0; i < tgts.targets.size(); i++) - { + //printf(" FOV (fx, fy) = (%.2f, %.2f)\n", tgts.fov_x, tgts.fov_y); + //for (int i = 0; i < tgts.targets.size(); i++) + //{ // 仅追踪 X 类型的标靶 - if (tgts.targets[i].category_id == 2) - { - gimbalTrack(tgts.targets[0].cx - 0.5f, tgts.targets[0].cy - 0.5f); - } + //if (tgts.targets[i].category_id == 2) + //{ + //gimbalTrack(tgts.targets[0].cx - 0.5f, tgts.targets[0].cy - 0.5f); + //} - printf("Frame-[%d], Marker-[%d]\n", frame_id, i); + //printf("Frame-[%d], Marker-[%d]\n", frame_id, i); // 打印每个 降落标志 的中心位置,cx,cy的值域为[0, 1] - printf(" Marker Center (cx, cy) = (%.3f, %.3f)\n", tgts.targets[i].cx, tgts.targets[i].cy); + //printf(" Marker Center (cx, cy) = (%.3f, %.3f)\n", tgts.targets[i].cx, tgts.targets[i].cy); // 打印每个 降落标志 的外接矩形框的宽度、高度,w,h的值域为(0, 1] - printf(" Marker Size (w, h) = (%.3f, %.3f)\n", tgts.targets[i].w, tgts.targets[i].h); + //printf(" Marker Size (w, h) = (%.3f, %.3f)\n", tgts.targets[i].w, tgts.targets[i].h); // 打印每个 降落标志 的置信度 - printf(" Marker Score = %.3f\n", tgts.targets[i].score); + //printf(" Marker Score = %.3f\n", tgts.targets[i].score); // 打印每个 降落标志 的类别,字符串类型,"h"、"x"、"1"、"2"、"3"... - printf(" Marker Category = %s, Category ID = %d\n", tgts.targets[i].category.c_str(), tgts.targets[i].category_id); + //printf(" Marker Category = %s, Category ID = %d\n", tgts.targets[i].category.c_str(), tgts.targets[i].category_id); // 打印每个 降落标志 的视线角,跟相机视场相关 - printf(" Marker Line-of-sight (ax, ay) = (%.3f, %.3f)\n", tgts.targets[i].los_ax, tgts.targets[i].los_ay); + //printf(" Marker Line-of-sight (ax, ay) = (%.3f, %.3f)\n", tgts.targets[i].los_ax, tgts.targets[i].los_ay); // 打印每个 降落标志 的3D位置(在相机坐标系下),跟降落标志实际半径、相机参数相关 - printf(" Marker Position = (x, y, z) = (%.3f, %.3f, %.3f)\n", tgts.targets[i].px, tgts.targets[i].py, tgts.targets[i].pz); - } + //printf(" Marker Position = (x, y, z) = (%.3f, %.3f, %.3f)\n", tgts.targets[i].px, tgts.targets[i].py, //tgts.targets[i].pz); + //} // 显示检测结果img cv::imshow(RGB_WINDOW, img); - cv::waitKey(10); + cv::waitKey(1); + } + auto time2 = std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count(); + auto Ts = time2 - time1; + std::cout << "Ts = " << Ts / (1000) << "us" << std::endl; } return 0; @@ -144,4 +151,4 @@ void GimableCallback(double &frame_ang_r, double &frame_ang_p, double &frame_ang count = 0; } count++; -} \ No newline at end of file +} diff --git a/samples/demo/gimbal_udp_detection_info_sender.cpp b/samples/demo/gimbal_udp_detection_info_sender.cpp index 00bfceb..4c5091e 100644 --- a/samples/demo/gimbal_udp_detection_info_sender.cpp +++ b/samples/demo/gimbal_udp_detection_info_sender.cpp @@ -79,6 +79,7 @@ int main(int argc, char *argv[]) sv::TargetsInFrame tgts(frame_id++); // 读取一帧图像到img cap.read(img); + continue; // 执行Aruco二维码检测 ad.detect(img, tgts); diff --git a/samples/demo/landing_marker_detection.cpp b/samples/demo/landing_marker_detection.cpp index ab36c2d..281c73b 100644 --- a/samples/demo/landing_marker_detection.cpp +++ b/samples/demo/landing_marker_detection.cpp @@ -2,7 +2,7 @@ #include // 包含SpireCV SDK头文件 #include - +#include using namespace std; int main(int argc, char *argv[]) { @@ -13,14 +13,18 @@ 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(640, 480); + cap.setFps(60); + cap.open(sv::CameraType::WEBCAM, 4); // CameraID 0 // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; int frame_id = 0; while (1) { + auto time1 = std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count(); + // 实例化SpireCV的 单帧检测结果 接口类 TargetsInFrame + for(uint j = 0; j < 60; j++) + { // 实例化SpireCV的 单帧检测结果 接口类 TargetsInFrame sv::TargetsInFrame tgts(frame_id++); // 读取一帧图像到img @@ -33,39 +37,43 @@ int main(int argc, char *argv[]) { sv::drawTargetsInFrame(img, tgts); // 控制台打印 降落标志 检测结果 - printf("Frame-[%d]\n", frame_id); + //printf("Frame-[%d]\n", frame_id); // 打印当前检测的FPS printf(" FPS = %.2f\n", tgts.fps); // 打印当前相机的视场角(degree) - printf(" FOV (fx, fy) = (%.2f, %.2f)\n", tgts.fov_x, tgts.fov_y); + //printf(" FOV (fx, fy) = (%.2f, %.2f)\n", tgts.fov_x, tgts.fov_y); // 打印当前输入图像的像素宽度和高度 - printf(" Frame Size (width, height) = (%d, %d)\n", tgts.width, tgts.height); + //printf(" Frame Size (width, height) = (%d, %d)\n", tgts.width, tgts.height); for (int i=0; i(std::chrono::system_clock::now().time_since_epoch()).count(); + auto Ts = time2 - time1; + std::cout << "Ts = " << Ts / (1000) << "us" << std::endl; } return 0; diff --git a/samples/demo/single_object_tracking.cpp b/samples/demo/single_object_tracking.cpp index ee4741f..37eebc9 100644 --- a/samples/demo/single_object_tracking.cpp +++ b/samples/demo/single_object_tracking.cpp @@ -28,15 +28,16 @@ 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_640x480.yaml"); + sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1280x720.yaml"); // sot.loadCameraParams(sv::get_home() + "/SpireCV/calib_webcam_1920x1080.yaml"); // 打开摄像头 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::WEBCAM, 4); // CameraID 0 + // cv::VideoCapture cap("/home/amov/SpireCV/test/tracking_1280x720.mp4"); // 实例化OpenCV的Mat类,用于内存单帧图像 cv::Mat img; diff --git a/samples/test/camera_fps_test.cpp b/samples/test/camera_fps_test.cpp new file mode 100644 index 0000000..468418f --- /dev/null +++ b/samples/test/camera_fps_test.cpp @@ -0,0 +1,34 @@ + +#include +#include +#include +#include + +int main(int argc, char *argv[]) +{ + sv::Camera cap; + cap.setIp(argv[1]); + cap.setWH(640, 480); + cap.setFps(60); + cap.open(sv::CameraType::G1); + + //cap.open(sv::CameraType::WEBCAM, 4); + + cv::Mat img; + //auto time1,time2; + + while (1) + { + auto time1 = std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count(); + //for (uint16_t i = 0; i < 120; i++) + //{ + cap.read(img); + cv::imshow("TEST",img); + cv::waitKey(1); + //} + auto time2 = std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count(); + auto Ts = time2 - time1; + std::cout << "read 120 count;Ts = " << Ts / (1000) << "us" << std::endl; + std::cout << "average FPS = " << (1000 * 1000 * 1000) / (Ts / 120) << std::endl; + } +} diff --git a/scripts/common/configs-downloading.sh b/scripts/common/configs-downloading.sh deleted file mode 100644 index 881cba5..0000000 --- a/scripts/common/configs-downloading.sh +++ /dev/null @@ -1,39 +0,0 @@ -#!/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 - diff --git a/scripts/common/ffmpeg425-install.sh b/scripts/common/ffmpeg425-install.sh index a1193c5..65b1ea4 100644 --- a/scripts/common/ffmpeg425-install.sh +++ b/scripts/common/ffmpeg425-install.sh @@ -2,7 +2,7 @@ sudo apt install -y \ -build-essential yasm cmake libtool libc6 libc6-dev unzip wget libeigen3-dev libfmt-dev \ +build-essential yasm cmake libtool libc6 libc6-dev unzip wget libfmt-dev \ libnuma1 libnuma-dev libx264-dev libx265-dev libfaac-dev libssl-dev root_dir=${HOME}"/SpireCV" diff --git a/scripts/common/gst-install-orin.sh b/scripts/common/gst-install-orin.sh index e1ca0e1..90510f5 100644 --- a/scripts/common/gst-install-orin.sh +++ b/scripts/common/gst-install-orin.sh @@ -8,7 +8,6 @@ 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 sudo apt -y install autotools-dev automake m4 perl sudo apt -y install libtool diff --git a/scripts/common/gst-install.sh b/scripts/common/gst-install.sh index a21e4b6..f629213 100644 --- a/scripts/common/gst-install.sh +++ b/scripts/common/gst-install.sh @@ -8,7 +8,6 @@ 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 git clone https://gitee.com/jario-jin/gst-rtsp-server-b18.git cd gst-rtsp-server-b18 diff --git a/scripts/jetson/opencv470-jetpack511-cuda-install.sh b/scripts/jetson/opencv470-jetpack511-cuda-install.sh deleted file mode 100644 index 068e35a..0000000 --- a/scripts/jetson/opencv470-jetpack511-cuda-install.sh +++ /dev/null @@ -1,54 +0,0 @@ -#!/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-4.7.0.zip - - -package_dir="." -mkdir ~/opencv_build - - -if [ ! -d ""$package_dir"" ];then - echo "\033[31m[ERROR]: $package_dir not exist!: \033[0m" - exit 1 -fi - -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 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 - - -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-4.7.0.zip ..." -unzip -q -o $package_dir/opencv_cache-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-4.7.0.zip - -cd ~/opencv_build/opencv-4.7.0 -mkdir .cache - -cp -r ~/opencv_build/opencv_cache-4.7.0/* ~/opencv_build/opencv-4.7.0/.cache/ - -mkdir build -cd build - -cmake -D CMAKE_BUILD_TYPE=Release -D WITH_CUDA=ON -D CUDA_ARCH_BIN=8.7 -D WITH_CUDNN=ON -D OPENCV_DNN_CUDA=ON -D WITH_CUBLAS=ON -D CUDA_TOOLKIT_ROOT_DIR=/usr/local/cuda -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 diff --git a/scripts/test/test_fps.sh b/scripts/test/test_fps.sh old mode 100755 new mode 100644 diff --git a/scripts/test/test_gimbal.sh b/scripts/test/test_gimbal.sh old mode 100755 new mode 100644 diff --git a/scripts/x86-cuda/x86-gst-install.sh b/scripts/x86-cuda/x86-gst-install.sh old mode 100755 new mode 100644 index a21e4b6..f629213 --- a/scripts/x86-cuda/x86-gst-install.sh +++ b/scripts/x86-cuda/x86-gst-install.sh @@ -8,7 +8,6 @@ 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 git clone https://gitee.com/jario-jin/gst-rtsp-server-b18.git cd gst-rtsp-server-b18 diff --git a/scripts/x86-cuda/x86-opencv470-cuda-install.sh b/scripts/x86-cuda/x86-opencv470-cuda-install.sh deleted file mode 100755 index c44e718..0000000 --- a/scripts/x86-cuda/x86-opencv470-cuda-install.sh +++ /dev/null @@ -1,69 +0,0 @@ -#!/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 - - -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 - - -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=ON \ - -D WITH_CUDNN=ON \ - -D OPENCV_DNN_CUDA=ON \ - -D WITH_CUBLAS=ON \ - -D CUDA_TOOLKIT_ROOT_DIR=/usr/local/cuda \ - -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 diff --git a/scripts/x86-cuda/x86-opencv470-install.sh b/scripts/x86-cuda/x86-opencv470-install.sh old mode 100755 new mode 100644 index df48173..d24a7f6 --- a/scripts/x86-cuda/x86-opencv470-install.sh +++ b/scripts/x86-cuda/x86-opencv470-install.sh @@ -20,12 +20,7 @@ fi 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 diff --git a/scripts/x86-cuda/x86-ubuntu2004-cuda-cudnn-11-6.sh b/scripts/x86-cuda/x86-ubuntu2004-cuda-cudnn-11-6.sh old mode 100755 new mode 100644 diff --git a/video_io/sv_video_base.cpp b/video_io/sv_video_base.cpp index 2b1af95..a0aa288 100644 --- a/video_io/sv_video_base.cpp +++ b/video_io/sv_video_base.cpp @@ -367,6 +367,7 @@ void UDPServer::send(const TargetsInFrame& tgts_) int r = sendto(this->_sockfd, upd_msg, mp, 0, (struct sockaddr *)&this->_servaddr, sizeof(this->_servaddr)); } + void drawTargetsInFrame( cv::Mat& img_, const TargetsInFrame& tgts_, @@ -418,6 +419,7 @@ void drawTargetsInFrame( } + void drawTargetsInFrame( cv::Mat& img_, const TargetsInFrame& tgts_, @@ -859,7 +861,7 @@ VideoWriterBase::VideoWriterBase() VideoWriterBase::~VideoWriterBase() { this->release(); - // this->_tt.join(); + this->_tt.join(); } cv::Size VideoWriterBase::getSize() { @@ -1041,7 +1043,7 @@ CameraBase::CameraBase(CameraType type, int id) CameraBase::~CameraBase() { this->_is_running = false; - // this->_tt.join(); + this->_tt.join(); } void CameraBase::setWH(int width, int height) { @@ -1153,33 +1155,57 @@ void CameraBase::_run() { while (this->_is_running && this->_cap.isOpened()) { - this->_cap >> this->_frame; - this->_is_updated = true; - std::this_thread::sleep_for(std::chrono::milliseconds(2)); + //this->_cap >> this->_frame; + //this->_is_updated = true; + //std::this_thread::sleep_for(std::chrono::milliseconds(2)); + + if(this->_cap.grab()) + { + std::lock_guard locker(this->_frame_mutex); + this->_cap.retrieve(this->_frame); + this->_frame_empty.notify_all(); + } + std::this_thread::sleep_for(std::chrono::milliseconds(1)); } } bool CameraBase::read(cv::Mat& image) { + bool ret = false; if (this->_type == CameraType::WEBCAM || this->_type == CameraType::G1 || this->_type == CameraType::MIPI) { - int n_try = 0; - while (n_try < 5000) + std::lock_guard locker(this->_frame_mutex); + if(this->_frame_empty.wait_for(this->_frame_mutex,std::chrono::milliseconds(2000)) == std::cv_status::no_timeout) { - if (this->_is_updated) - { - this->_is_updated = false; - this->_frame.copyTo(image); - break; - } - std::this_thread::sleep_for(std::chrono::milliseconds(20)); - n_try ++; + this->_frame.copyTo(image); + ret = true; + } + else + { + throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!"); } } - if (image.cols == 0 || image.rows == 0) - { - throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!"); - } - return image.cols > 0 && image.rows > 0; + return ret; + + if (this->_type == CameraType::WEBCAM || this->_type == CameraType::G1 || this->_type == CameraType::MIPI) + { + int n_try = 0; + while (n_try < 5000) + { + if (this->_is_updated) + { + this->_is_updated = false; + this->_frame.copyTo(image); + break; + } + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + n_try ++; + } + } + if (image.cols == 0 || image.rows == 0) + { + throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!"); + } + return image.cols > 0 && image.rows > 0; } void CameraBase::release() { diff --git a/video_io/sv_video_input.cpp b/video_io/sv_video_input.cpp index 5ca7bfa..60f0319 100644 --- a/video_io/sv_video_input.cpp +++ b/video_io/sv_video_input.cpp @@ -79,6 +79,7 @@ void Camera::openImpl() else if (this->_type == CameraType::MIPI) { char pipe[512]; + this->_cap.open(this->_camera_id); if (this->_width <= 0 || this->_height <= 0) { this->_width = 1280; @@ -89,7 +90,7 @@ 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 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->_fps,this->_width,this->_height); this->_cap.open(pipe, cv::CAP_GSTREAMER); } }