forked from logzhan/RobotKernal-UESTC
优化部分注释内容,重构部分函数名更加符合其作用
parent
ce2f195559
commit
326173660f
|
@ -51,6 +51,6 @@ public:
|
||||||
void getInfo(cv::Mat &imgl, cv::Mat &imgr, cv::Mat &detBoxes, cv::Mat &info);
|
void getInfo(cv::Mat &imgl, cv::Mat &imgr, cv::Mat &detBoxes, cv::Mat &info);
|
||||||
std::vector<float> pic2cam(int u, int v);
|
std::vector<float> pic2cam(int u, int v);
|
||||||
std::vector<int> muban(cv::Mat &left_image, cv::Mat &right_image, const int *coordinates);
|
std::vector<int> muban(cv::Mat &left_image, cv::Mat &right_image, const int *coordinates);
|
||||||
std::vector<cv::Mat> get_range();
|
std::vector<cv::Mat> detObjectRanging();
|
||||||
void horizon_estimate(cv::Mat& img, cv::Mat& bboxs,int k);
|
void horizon_estimate(cv::Mat& img, cv::Mat& bboxs,int k);
|
||||||
};
|
};
|
||||||
|
|
|
@ -1,7 +1,13 @@
|
||||||
|
/******************** (C) COPYRIGHT 2024 UPBot **********************************
|
||||||
|
* File Name : detection.cpp
|
||||||
|
* Current Version : V1.0
|
||||||
|
* Author : Rockchip & linyuehang
|
||||||
|
* Date of Issued : 2024.01.07 zhanli@review
|
||||||
|
* Comments : 目标检测类,负责调用瑞芯微芯片NPU进行目标检测推理
|
||||||
|
********************************************************************************/
|
||||||
#include "detection.h"
|
#include "detection.h"
|
||||||
#include <opencv2/opencv.hpp>
|
#include <opencv2/opencv.hpp>
|
||||||
|
|
||||||
|
|
||||||
unsigned char * Detection::load_data(FILE *fp, size_t ofst, size_t sz)
|
unsigned char * Detection::load_data(FILE *fp, size_t ofst, size_t sz)
|
||||||
{
|
{
|
||||||
unsigned char *data;
|
unsigned char *data;
|
||||||
|
|
|
@ -1,3 +1,9 @@
|
||||||
|
/******************** (C) COPYRIGHT 2024 UPBot **********************************
|
||||||
|
* File Name : main.cpp
|
||||||
|
* Current Version : V1.0
|
||||||
|
* Date of Issued : 2024.01.96 zhanli@review
|
||||||
|
* Comments : UPbot机器人双目目标测距算法
|
||||||
|
********************************************************************************/
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
// #include "lidar.h"
|
// #include "lidar.h"
|
||||||
|
@ -23,12 +29,18 @@ Ranging r(12, 640, 480);
|
||||||
std::queue<std::vector<cv::Mat>> frameInfo;
|
std::queue<std::vector<cv::Mat>> frameInfo;
|
||||||
std::mutex g_mutex;
|
std::mutex g_mutex;
|
||||||
|
|
||||||
void *ranging(void *args) // ranging线程
|
/**---------------------------------------------------------------------
|
||||||
|
* Function : RangingNodeTask
|
||||||
|
* Description : 双目测距节点任务,完成摄像头帧读取、目标检测以及目标测距任务
|
||||||
|
* Author : hongchuyuan
|
||||||
|
* Date : 2023/12/13 zhanli@review 719901725@qq.com
|
||||||
|
*---------------------------------------------------------------------**/
|
||||||
|
void *RangingNodeTask(void *args)
|
||||||
{
|
{
|
||||||
while (true)
|
while (true)
|
||||||
{
|
{
|
||||||
// std::cout<<" ************ enter ranging *********** "<<std::endl;
|
// std::cout<<" ************ enter ranging *********** "<<std::endl;
|
||||||
std::vector<cv::Mat> result = r.get_range();
|
std::vector<cv::Mat> result = r.detObjectRanging();
|
||||||
g_mutex.lock();
|
g_mutex.lock();
|
||||||
for (uchar i = 0; i < frameInfo.size(); i++) // 只保存当前最新的图片帧信息
|
for (uchar i = 0; i < frameInfo.size(); i++) // 只保存当前最新的图片帧信息
|
||||||
frameInfo.pop();
|
frameInfo.pop();
|
||||||
|
@ -40,11 +52,10 @@ void *ranging(void *args) // ranging线程
|
||||||
int main(int argc, char **argv)
|
int main(int argc, char **argv)
|
||||||
{
|
{
|
||||||
pthread_t tids[1]; // 执行ranging线程
|
pthread_t tids[1]; // 执行ranging线程
|
||||||
int ret = pthread_create(&tids[0], NULL, ranging, NULL);
|
int ret = pthread_create(&tids[0], NULL, RangingNodeTask, NULL);
|
||||||
|
|
||||||
while(1){
|
while(1){
|
||||||
usleep(150000);
|
usleep(150000);
|
||||||
}
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,3 +1,10 @@
|
||||||
|
/******************** (C) COPYRIGHT 2024 UPBot **********************************
|
||||||
|
* File Name : ranging.cpp
|
||||||
|
* Current Version : V1.0
|
||||||
|
* Author : Rockchip & linyuehang
|
||||||
|
* Date of Issued : 2024.01.07 zhanli@review
|
||||||
|
* Comments : 双目摄像头目标测距算法,需要依赖OpenCV以及目标检测模块
|
||||||
|
********************************************************************************/
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include "ranging.h"
|
#include "ranging.h"
|
||||||
|
@ -297,8 +304,9 @@ Ranging::Ranging(int index, int imgw, int imgh) : //初始化
|
||||||
auto imgSize = Size(imgw, imgh);
|
auto imgSize = Size(imgw, imgh);
|
||||||
Mat r1(3, 3, CV_64F), r2(3, 3, CV_64F), p1(3, 4, CV_64F), p2(3, 4, CV_64F);
|
Mat r1(3, 3, CV_64F), r2(3, 3, CV_64F), p1(3, 4, CV_64F), p2(3, 4, CV_64F);
|
||||||
|
|
||||||
|
// 立体校正
|
||||||
stereoRectify(cam_matrix_left.t(), distortion_l, cam_matrix_right.t(), distortion_r,
|
stereoRectify(cam_matrix_left.t(), distortion_l, cam_matrix_right.t(), distortion_r,
|
||||||
imgSize, rotate.t(), trans, r1, r2, p1, p2, q);//立体校正
|
imgSize, rotate.t(), trans, r1, r2, p1, p2, q);
|
||||||
|
|
||||||
// 计算无畸变和修正转换映射
|
// 计算无畸变和修正转换映射
|
||||||
initUndistortRectifyMap(cam_matrix_left.t(), distortion_l, r1, p1, imgSize, CV_32F, mapX1, mapX2);
|
initUndistortRectifyMap(cam_matrix_left.t(), distortion_l, r1, p1, imgSize, CV_32F, mapX1, mapX2);
|
||||||
|
@ -309,8 +317,13 @@ Ranging::Ranging(int index, int imgw, int imgh) : //初始化
|
||||||
std::cout<< " ******************* CAMERA initialization ********************" << std::endl;
|
std::cout<< " ******************* CAMERA initialization ********************" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**---------------------------------------------------------------------
|
||||||
std::vector<Mat> Ranging::get_range()
|
* Function : detObjectRanging
|
||||||
|
* Description : 摄像头帧读取、目标检测以及目标测距任务
|
||||||
|
* Author : hongchuyuan
|
||||||
|
* Date : 2023/12/13 zhanli@review 719901725@qq.com
|
||||||
|
*---------------------------------------------------------------------**/
|
||||||
|
std::vector<Mat> Ranging::detObjectRanging()
|
||||||
{
|
{
|
||||||
|
|
||||||
double rang_old, rang_now;
|
double rang_old, rang_now;
|
||||||
|
@ -378,7 +391,7 @@ std::vector<Mat> Ranging::get_range()
|
||||||
// }
|
// }
|
||||||
}
|
}
|
||||||
|
|
||||||
// 存储测距信息,存储格式:距离d,宽w,高h,角度α
|
// 存储测距信息,存储格式:距离d,宽w,高h,角度alpha
|
||||||
Mat info(detect_result_group.count, 4, CV_32F);
|
Mat info(detect_result_group.count, 4, CV_32F);
|
||||||
|
|
||||||
// 如果有检测目标
|
// 如果有检测目标
|
||||||
|
@ -386,7 +399,7 @@ std::vector<Mat> Ranging::get_range()
|
||||||
{
|
{
|
||||||
// getInfo()修改为calObjectRanging()
|
// getInfo()修改为calObjectRanging()
|
||||||
// 在这里测量目标的距离并存储到info中
|
// 在这里测量目标的距离并存储到info中
|
||||||
// 优化: 这个地方重复的将左右视图转换为灰度图,浪费CPU的算力
|
// 优化:这个地方重复的将左右视图转换为灰度图,浪费CPU的算力
|
||||||
getInfo(lframe, rframe, detBoxes, info);
|
getInfo(lframe, rframe, detBoxes, info);
|
||||||
|
|
||||||
//show stereo distance
|
//show stereo distance
|
||||||
|
|
Loading…
Reference in New Issue