forked from floratest1/SpireCV
update.
This commit is contained in:
parent
ddb157b374
commit
fb2a60e3ca
|
@ -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<float>& boxes_h_,
|
||||
std::vector<int>& boxes_label_,
|
||||
std::vector<float>& boxes_score_,
|
||||
std::vector<cv::Mat>& boxes_seg_,
|
||||
bool input_4k_
|
||||
std::vector<cv::Mat>& boxes_seg_
|
||||
)
|
||||
{
|
||||
#ifdef WITH_CUDA
|
||||
|
@ -184,51 +183,9 @@ void CommonObjectDetectorCUDAImpl::cudaDetect(
|
|||
double thrs_nms = base_->getThrsNms();
|
||||
|
||||
std::vector<cv::Mat> 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);
|
||||
}
|
||||
|
||||
// Run inference
|
||||
if (with_segmentation)
|
||||
|
@ -236,16 +193,9 @@ void CommonObjectDetectorCUDAImpl::cudaDetect(
|
|||
infer_seg(*this->_context, this->_stream, (void**)this->_gpu_buffers, this->_cpu_output_buffer1, this->_cpu_output_buffer2, kBatchSize);
|
||||
}
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
// NMS
|
||||
std::vector<std::vector<Detection>> res_batch;
|
||||
|
@ -258,63 +208,6 @@ void CommonObjectDetectorCUDAImpl::cudaDetect(
|
|||
batch_nms(res_batch, this->_cpu_output_buffer, img_batch.size(), kOutputSize, thrs_conf, thrs_nms);
|
||||
}
|
||||
|
||||
|
||||
if (input_4k_)
|
||||
{
|
||||
for (size_t k = 0; k < res_batch.size(); k++)
|
||||
{
|
||||
std::vector<Detection> 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);
|
||||
|
||||
boxes_label_.push_back((int)res[j].class_id);
|
||||
boxes_score_.push_back(res[j].conf);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
std::vector<Detection> res = res_batch[0];
|
||||
std::vector<cv::Mat> masks;
|
||||
if (with_segmentation)
|
||||
|
@ -322,8 +215,9 @@ void CommonObjectDetectorCUDAImpl::cudaDetect(
|
|||
masks = process_mask(&(this->_cpu_output_buffer2[0]), kOutputSize2, res, input_h, input_w);
|
||||
}
|
||||
|
||||
for (size_t j = 0; j < res.size(); j++)
|
||||
{
|
||||
|
||||
|
||||
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;
|
||||
|
@ -349,11 +243,10 @@ void CommonObjectDetectorCUDAImpl::cudaDetect(
|
|||
}
|
||||
}
|
||||
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
bool CommonObjectDetectorCUDAImpl::cudaSetup(CommonObjectDetectorBase* base_, bool input_4k_)
|
||||
bool CommonObjectDetectorCUDAImpl::cudaSetup(CommonObjectDetectorBase* base_)
|
||||
{
|
||||
#ifdef WITH_CUDA
|
||||
std::string dataset = base_->getDataset();
|
||||
|
@ -380,11 +273,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);
|
||||
}
|
||||
else
|
||||
{
|
||||
if (input_4k_)
|
||||
{
|
||||
// Prepare cpu and gpu buffers
|
||||
this->_prepare_buffers(input_h, input_w, 6);
|
||||
this->_prepare_buffers_seg(input_h, input_w);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Prepare cpu and gpu buffers
|
||||
this->_prepare_buffers(input_h, input_w, 1);
|
||||
}
|
||||
this->_prepare_buffers(input_h, input_w);
|
||||
}
|
||||
return true;
|
||||
#endif
|
||||
|
|
|
@ -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<float>& boxes_h_,
|
||||
std::vector<int>& boxes_label_,
|
||||
std::vector<float>& boxes_score_,
|
||||
std::vector<cv::Mat>& boxes_seg_,
|
||||
bool input_4k_
|
||||
std::vector<cv::Mat>& 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;
|
||||
|
|
|
@ -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
|
||||
}
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -11,21 +11,18 @@
|
|||
#define SV_MODEL_DIR "/SpireCV/models/"
|
||||
#define SV_ROOT_DIR "/SpireCV/"
|
||||
|
||||
|
||||
namespace sv {
|
||||
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_)
|
||||
{
|
||||
fov_x_ = 2 * atan(img_w_ / 2. / camera_matrix_.at<double>(0, 0)) * SV_RAD2DEG;
|
||||
fov_y_ = 2 * atan(img_h_ / 2. / camera_matrix_.at<double>(1, 1)) * SV_RAD2DEG;
|
||||
}
|
||||
|
||||
|
||||
|
||||
CameraAlgorithm::CameraAlgorithm()
|
||||
{
|
||||
// this->_value = NULL;
|
||||
|
@ -66,20 +63,17 @@ void CameraAlgorithm::loadCameraParams(std::string yaml_fn_)
|
|||
// 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;
|
||||
|
@ -93,63 +87,79 @@ void ArucoDetector::_load()
|
|||
_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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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();
|
||||
|
@ -170,109 +180,139 @@ void ArucoDetector::_load()
|
|||
_detector_params->cornerRefinementMethod = cv::aruco::CornerRefineMethod::CORNER_REFINE_NONE;
|
||||
}
|
||||
}
|
||||
else if ("cornerRefinementMinAccuracy" == std::string(i->key)) {
|
||||
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)) {
|
||||
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)) {
|
||||
else if ("detectInvertedMarker" == std::string(i->key))
|
||||
{
|
||||
bool json_tf = false;
|
||||
if (i->value.getTag() == JSON_TRUE) json_tf = true;
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
else if ("useAruco3Detection" == std::string(i->key))
|
||||
{
|
||||
bool json_tf = false;
|
||||
if (i->value.getTag() == JSON_TRUE) json_tf = true;
|
||||
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) {
|
||||
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) {
|
||||
for (auto j : i->value)
|
||||
{
|
||||
if (jcnt == 0 && j->value.toNumber() == -1)
|
||||
{
|
||||
_ids_need.push_back(-1);
|
||||
break;
|
||||
}
|
||||
else {
|
||||
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) {
|
||||
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 {
|
||||
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()) {
|
||||
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!");
|
||||
}
|
||||
|
||||
|
@ -282,7 +322,6 @@ void ArucoDetector::_load()
|
|||
// std::cout << "_lengths_need: " << l << std::endl;
|
||||
}
|
||||
|
||||
|
||||
void ArucoDetector::detect(cv::Mat img_, TargetsInFrame &tgts_)
|
||||
{
|
||||
if (!_params_loaded)
|
||||
|
@ -311,7 +350,6 @@ void ArucoDetector::detect(cv::Mat img_, TargetsInFrame& tgts_)
|
|||
// detect markers and estimate pose
|
||||
aruco::detectMarkers(img_, this->_dictionary, corners, ids, _detector_params, rejected);
|
||||
|
||||
|
||||
if (ids.size() > 0)
|
||||
{
|
||||
if (_ids_need[0] == -1)
|
||||
|
@ -383,8 +421,6 @@ void ArucoDetector::detect(cv::Mat img_, TargetsInFrame& tgts_)
|
|||
// waitKey(10);
|
||||
}
|
||||
|
||||
|
||||
|
||||
EllipseDetector::EllipseDetector()
|
||||
{
|
||||
this->_ed = NULL;
|
||||
|
@ -393,7 +429,11 @@ EllipseDetector::EllipseDetector()
|
|||
}
|
||||
EllipseDetector::~EllipseDetector()
|
||||
{
|
||||
if (_ed) { delete _ed; _ed = NULL; }
|
||||
if (_ed)
|
||||
{
|
||||
delete _ed;
|
||||
_ed = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
void EllipseDetector::detect(cv::Mat img_, TargetsInFrame &tgts_)
|
||||
|
@ -435,10 +475,8 @@ LandingMarkerDetectorBase::LandingMarkerDetectorBase()
|
|||
setupImpl();
|
||||
}
|
||||
|
||||
|
||||
LandingMarkerDetectorBase::~LandingMarkerDetectorBase()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
bool LandingMarkerDetectorBase::isParamsLoaded()
|
||||
|
@ -454,7 +492,6 @@ std::vector<std::string> LandingMarkerDetectorBase::getLabelsNeed()
|
|||
return this->_labels_need;
|
||||
}
|
||||
|
||||
|
||||
void LandingMarkerDetectorBase::detect(cv::Mat img_, TargetsInFrame &tgts_)
|
||||
{
|
||||
if (!_params_loaded)
|
||||
|
@ -489,11 +526,16 @@ void LandingMarkerDetectorBase::detect(cv::Mat img_, TargetsInFrame& tgts_)
|
|||
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;
|
||||
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;
|
||||
|
@ -521,7 +563,8 @@ void LandingMarkerDetectorBase::detect(cv::Mat img_, TargetsInFrame& tgts_)
|
|||
need = true;
|
||||
}
|
||||
}
|
||||
if (!need) label = 0;
|
||||
if (!need)
|
||||
label = 0;
|
||||
|
||||
yaed::Ellipse e = ellsCned[i];
|
||||
if (label > 0)
|
||||
|
@ -541,10 +584,8 @@ bool LandingMarkerDetectorBase::setupImpl()
|
|||
}
|
||||
void LandingMarkerDetectorBase::roiCNN(std::vector<cv::Mat> &input_rois_, std::vector<int> &output_labels_)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
void LandingMarkerDetectorBase::_loadLabels()
|
||||
{
|
||||
JsonValue all_value;
|
||||
|
@ -554,13 +595,17 @@ void LandingMarkerDetectorBase::_loadLabels()
|
|||
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) {
|
||||
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)) {
|
||||
else if ("maxCandidates" == std::string(i->key))
|
||||
{
|
||||
this->_max_candidates = i->value.toNumber();
|
||||
// std::cout << "maxCandidates: " << this->_max_candidates << std::endl;
|
||||
}
|
||||
|
@ -568,7 +613,6 @@ void LandingMarkerDetectorBase::_loadLabels()
|
|||
setupImpl();
|
||||
}
|
||||
|
||||
|
||||
void EllipseDetector::detectAllInDirectory(std::string input_img_dir_, std::string output_json_dir_)
|
||||
{
|
||||
if (!_params_loaded)
|
||||
|
@ -652,88 +696,107 @@ void EllipseDetector::_load()
|
|||
float fT_TCN_P;
|
||||
float fThre_R;
|
||||
|
||||
for (auto i : ell_params_value) {
|
||||
if ("preProcessingGaussKernel" == std::string(i->key)) {
|
||||
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)) {
|
||||
else if ("preProcessingGaussSigma" == std::string(i->key))
|
||||
{
|
||||
dPreProcessingGaussSigma = i->value.toNumber();
|
||||
// std::cout << "preProcessingGaussSigma: " << dPreProcessingGaussSigma << std::endl;
|
||||
}
|
||||
else if ("thPosition" == std::string(i->key)) {
|
||||
else if ("thPosition" == std::string(i->key))
|
||||
{
|
||||
fThPosition = i->value.toNumber();
|
||||
// std::cout << "thPosition: " << fThPosition << std::endl;
|
||||
}
|
||||
else if ("maxCenterDistance" == std::string(i->key)) {
|
||||
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)) {
|
||||
else if ("minEdgeLength" == std::string(i->key))
|
||||
{
|
||||
iMinEdgeLength = i->value.toNumber();
|
||||
// std::cout << "minEdgeLength: " << iMinEdgeLength << std::endl;
|
||||
}
|
||||
else if ("minOrientedRectSide" == std::string(i->key)) {
|
||||
else if ("minOrientedRectSide" == std::string(i->key))
|
||||
{
|
||||
fMinOrientedRectSide = i->value.toNumber();
|
||||
// std::cout << "minOrientedRectSide: " << fMinOrientedRectSide << std::endl;
|
||||
}
|
||||
else if ("distanceToEllipseContour" == std::string(i->key)) {
|
||||
else if ("distanceToEllipseContour" == std::string(i->key))
|
||||
{
|
||||
fDistanceToEllipseContour = i->value.toNumber();
|
||||
// std::cout << "distanceToEllipseContour: " << fDistanceToEllipseContour << std::endl;
|
||||
}
|
||||
else if ("minScore" == std::string(i->key)) {
|
||||
else if ("minScore" == std::string(i->key))
|
||||
{
|
||||
fMinScore = i->value.toNumber();
|
||||
// std::cout << "minScore: " << fMinScore << std::endl;
|
||||
}
|
||||
else if ("minReliability" == std::string(i->key)) {
|
||||
else if ("minReliability" == std::string(i->key))
|
||||
{
|
||||
fMinReliability = i->value.toNumber();
|
||||
// std::cout << "minReliability: " << fMinReliability << std::endl;
|
||||
}
|
||||
else if ("ns" == std::string(i->key)) {
|
||||
else if ("ns" == std::string(i->key))
|
||||
{
|
||||
iNs = i->value.toNumber();
|
||||
// std::cout << "ns: " << iNs << std::endl;
|
||||
}
|
||||
else if ("percentNe" == std::string(i->key)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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; }
|
||||
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()
|
||||
{
|
||||
|
@ -751,6 +814,18 @@ 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()
|
||||
{
|
||||
|
@ -796,6 +871,24 @@ void SingleObjectTrackerBase::track(cv::Mat img_, TargetsInFrame& tgts_)
|
|||
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));
|
||||
|
||||
if (this->_use_width_or_height == 0)
|
||||
{
|
||||
double z = this->camera_matrix.at<double>(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<double>(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);
|
||||
}
|
||||
|
||||
tgts_.targets.push_back(tgt);
|
||||
}
|
||||
|
||||
|
@ -807,7 +900,6 @@ bool SingleObjectTrackerBase::setupImpl()
|
|||
}
|
||||
void SingleObjectTrackerBase::initImpl(cv::Mat img_, const cv::Rect &bounding_box_)
|
||||
{
|
||||
|
||||
}
|
||||
bool SingleObjectTrackerBase::trackImpl(cv::Mat img_, cv::Rect &output_bbox_)
|
||||
{
|
||||
|
@ -822,23 +914,38 @@ void SingleObjectTrackerBase::_load()
|
|||
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)) {
|
||||
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)) {
|
||||
else if ("backend" == std::string(i->key))
|
||||
{
|
||||
this->_backend = i->value.toNumber();
|
||||
}
|
||||
else if ("target" == std::string(i->key)) {
|
||||
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();
|
||||
}
|
||||
|
||||
|
||||
CommonObjectDetectorBase::CommonObjectDetectorBase() // : CameraAlgorithm()
|
||||
{
|
||||
this->_params_loaded = false;
|
||||
|
@ -846,7 +953,6 @@ CommonObjectDetectorBase::CommonObjectDetectorBase() // : CameraAlgorithm()
|
|||
}
|
||||
CommonObjectDetectorBase::~CommonObjectDetectorBase()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
bool CommonObjectDetectorBase::isParamsLoaded()
|
||||
|
@ -958,10 +1064,14 @@ void CommonObjectDetectorBase::detect(cv::Mat img_, TargetsInFrame& tgts_, Box*
|
|||
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 (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)
|
||||
{
|
||||
Target tgt;
|
||||
|
@ -1046,10 +1156,8 @@ void CommonObjectDetectorBase::detectImpl(
|
|||
std::vector<float> &boxes_h_,
|
||||
std::vector<int> &boxes_label_,
|
||||
std::vector<float> &boxes_score_,
|
||||
std::vector<cv::Mat>& boxes_seg_
|
||||
)
|
||||
std::vector<cv::Mat> &boxes_seg_)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void CommonObjectDetectorBase::_load()
|
||||
|
@ -1070,13 +1178,16 @@ void CommonObjectDetectorBase::_load()
|
|||
this->_thrs_conf = 0.4;
|
||||
this->_use_width_or_height = 0;
|
||||
|
||||
for (auto i : detector_params_value) {
|
||||
for (auto i : detector_params_value)
|
||||
{
|
||||
|
||||
if ("dataset" == std::string(i->key)) {
|
||||
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)) {
|
||||
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)
|
||||
|
@ -1085,35 +1196,46 @@ void CommonObjectDetectorBase::_load()
|
|||
}
|
||||
this->_input_h = this->_input_w;
|
||||
}
|
||||
else if ("nmsThrs" == std::string(i->key)) {
|
||||
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)) {
|
||||
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)) {
|
||||
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)) {
|
||||
else if ("withSegmentation" == std::string(i->key))
|
||||
{
|
||||
bool json_tf = false;
|
||||
if (i->value.getTag() == JSON_TRUE) json_tf = true;
|
||||
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) {
|
||||
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) {
|
||||
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());
|
||||
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++;
|
||||
}
|
||||
}
|
||||
|
@ -1123,20 +1245,7 @@ void CommonObjectDetectorBase::_load()
|
|||
}
|
||||
|
||||
setupImpl();
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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;
|
||||
};
|
||||
|
||||
|
||||
|
|
|
@ -12,6 +12,9 @@
|
|||
#include <arpa/inet.h>
|
||||
#include <netinet/in.h> // for sockaddr_in
|
||||
|
||||
#include <mutex>
|
||||
#include <condition_variable>
|
||||
|
||||
#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<std::string>& files, std::string suff
|
|||
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
// 包含SpireCV SDK头文件
|
||||
#include <sv_world.h>
|
||||
// #include "gimbal_tools.hpp"
|
||||
|
||||
#include <chrono>
|
||||
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::nanoseconds>(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::nanoseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
|
||||
auto Ts = time2 - time1;
|
||||
std::cout << "Ts = " << Ts / (1000) << "us" << std::endl;
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
#include <string>
|
||||
// 包含SpireCV SDK头文件
|
||||
#include <sv_world.h>
|
||||
|
||||
#include <chrono>
|
||||
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::nanoseconds>(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,40 +37,44 @@ 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<tgts.targets.size(); i++)
|
||||
{
|
||||
printf("Frame-[%d], Marker-[%d]\n", frame_id, i);
|
||||
//printf("Frame-[%d], Marker-[%d]\n", frame_id, i);
|
||||
// 打印每个 降落标志 的中心位置,cx,cy的值域为[0, 1],以及cx,cy的像素值
|
||||
printf(" Marker Center (cx, cy) = (%.3f, %.3f), in Pixels = ((%d, %d))\n",
|
||||
tgts.targets[i].cx, tgts.targets[i].cy,
|
||||
int(tgts.targets[i].cx * tgts.width),
|
||||
int(tgts.targets[i].cy * tgts.height));
|
||||
//printf(" Marker Center (cx, cy) = (%.3f, %.3f), in Pixels = ((%d, %d))\n",
|
||||
//tgts.targets[i].cx, tgts.targets[i].cy,
|
||||
//int(tgts.targets[i].cx * tgts.width),
|
||||
//int(tgts.targets[i].cy * tgts.height));
|
||||
// 打印每个 降落标志 的外接矩形框的宽度、高度,w,h的值域为(0, 1],以及w,h的像素值
|
||||
printf(" Marker Size (w, h) = (%.3f, %.3f), in Pixels = ((%d, %d))\n",
|
||||
tgts.targets[i].w, tgts.targets[i].h,
|
||||
int(tgts.targets[i].w * tgts.width),
|
||||
int(tgts.targets[i].h * tgts.height));
|
||||
//printf(" Marker Size (w, h) = (%.3f, %.3f), in Pixels = ((%d, %d))\n",
|
||||
//tgts.targets[i].w, tgts.targets[i].h,
|
||||
//int(tgts.targets[i].w * tgts.width),
|
||||
//int(tgts.targets[i].h * tgts.height));
|
||||
// 打印每个 降落标志 的置信度
|
||||
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("img", img);
|
||||
cv::waitKey(10);
|
||||
}
|
||||
auto time2 = std::chrono::duration_cast<std::chrono::nanoseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
|
||||
auto Ts = time2 - time1;
|
||||
std::cout << "Ts = " << Ts / (1000) << "us" << std::endl;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -0,0 +1,34 @@
|
|||
|
||||
#include <sv_world.h>
|
||||
#include <iostream>
|
||||
#include <string>
|
||||
#include <chrono>
|
||||
|
||||
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::nanoseconds>(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::nanoseconds>(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;
|
||||
}
|
||||
}
|
|
@ -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
|
||||
|
|
@ -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"
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
|
@ -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
|
||||
|
|
|
@ -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
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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,13 +1155,37 @@ 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<std::mutex> 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)
|
||||
{
|
||||
std::lock_guard<std::mutex> locker(this->_frame_mutex);
|
||||
if(this->_frame_empty.wait_for(this->_frame_mutex,std::chrono::milliseconds(2000)) == std::cv_status::no_timeout)
|
||||
{
|
||||
this->_frame.copyTo(image);
|
||||
ret = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!");
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
|
||||
if (this->_type == CameraType::WEBCAM || this->_type == CameraType::G1 || this->_type == CameraType::MIPI)
|
||||
{
|
||||
int n_try = 0;
|
||||
|
@ -1171,7 +1197,7 @@ bool CameraBase::read(cv::Mat& image)
|
|||
this->_frame.copyTo(image);
|
||||
break;
|
||||
}
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(20));
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(10));
|
||||
n_try ++;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue