|
@@ -47,13 +47,21 @@
|
|
|
#include "ivversion.h"
|
|
|
#include <thread>
|
|
|
#include "objectarray.pb.h"
|
|
|
+#include "config.h"
|
|
|
|
|
|
#define M_PI 3.14159265358979323846
|
|
|
|
|
|
-const std::string gSampleName = "TensorRT.sample_onnx_centerpoint";
|
|
|
|
|
|
-float threshold = 0.5;
|
|
|
+////////////////////用于nms////////////////////
|
|
|
+#include<opencv2/opencv.hpp>
|
|
|
+#define rad2Angle(rad) ((rad) * 180.0 / M_PI)
|
|
|
+
|
|
|
+float smallinbig_threshold = 0.8;
|
|
|
+float distance_threshold = 0.2;
|
|
|
+float second_nms_threshold = 0.5;
|
|
|
+
|
|
|
|
|
|
+const std::string gSampleName = "TensorRT.sample_onnx_centerpoint";
|
|
|
CenterPoint * centerpoint = nullptr ;
|
|
|
|
|
|
iv::Ivfault *gfault = nullptr;
|
|
@@ -68,6 +76,150 @@ void * gpdetect;
|
|
|
|
|
|
string lidarname = "lidar_pc";
|
|
|
string detectname = "lidar_track";
|
|
|
+char gstr_memname[256];
|
|
|
+static const char *labels[] = {"car","bus","truck","alien_vehicle","non_motor_vehicle",
|
|
|
+ "pedestrain","cyclist","traffic_cone"};
|
|
|
+
|
|
|
+
|
|
|
+void print_useage()
|
|
|
+{
|
|
|
+ std::cout<<" -m --memname $mappath : share memory name. eq. -m lidar_pc"<<std::endl;
|
|
|
+ std::cout<<" -h --help print help"<<std::endl;
|
|
|
+}
|
|
|
+
|
|
|
+int GetOptLong(int argc, char *argv[]) {
|
|
|
+ int nRtn = 0;
|
|
|
+ int opt; // getopt_long() 的返回值
|
|
|
+ int digit_optind = 0; // 设置短参数类型及是否需要参数
|
|
|
+ // 如果option_index非空,它指向的变量将记录当前找到参数符合long_opts里的
|
|
|
+ // 第几个元素的描述,即是long_opts的下标值
|
|
|
+ int option_index = 0;
|
|
|
+ // 设置短参数类型及是否需要参数
|
|
|
+ const char *optstring = "m:h";
|
|
|
+ static struct option long_options[] = {
|
|
|
+ {"memname", required_argument, NULL, 'm'},
|
|
|
+ {"help", no_argument, NULL, 'h'},
|
|
|
+ // {"optarg", optional_argument, NULL, 'o'},
|
|
|
+ {0, 0, 0, 0} // 添加 {0, 0, 0, 0} 是为了防止输入空值
|
|
|
+ };
|
|
|
+
|
|
|
+ while ( (opt = getopt_long(argc,
|
|
|
+ argv,
|
|
|
+ optstring,
|
|
|
+ long_options,
|
|
|
+ &option_index)) != -1) {
|
|
|
+ switch(opt)
|
|
|
+ {
|
|
|
+ case 'm':
|
|
|
+ strncpy(gstr_memname,optarg,255);
|
|
|
+ break;
|
|
|
+ case 'h':
|
|
|
+ print_useage();
|
|
|
+ nRtn = 1; //because use -h
|
|
|
+ break;
|
|
|
+ default:
|
|
|
+ break;
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+ return nRtn;
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+/////////////nms算法去除重叠交叉的框/////////////
|
|
|
+typedef struct {
|
|
|
+ cv::RotatedRect box;
|
|
|
+ Box detection;
|
|
|
+ int label;
|
|
|
+ float score;
|
|
|
+}BBOX3D;
|
|
|
+
|
|
|
+//将检测结果转为RotatedRect以便于nms计算
|
|
|
+bool GetRotatedRect(std::vector<Box> &out_detections, std::vector<BBOX3D> &results)
|
|
|
+{
|
|
|
+ int obj_size = out_detections.size();
|
|
|
+ if(obj_size>0)
|
|
|
+ {
|
|
|
+ for(int i=0;i<obj_size;i++)
|
|
|
+ {
|
|
|
+ BBOX3D result;
|
|
|
+ result.box = cv::RotatedRect(cv::Point2f(out_detections[i].x,out_detections[i].y),
|
|
|
+ cv::Size2f(out_detections[i].l,out_detections[i].w),
|
|
|
+ rad2Angle(out_detections[i].theta));
|
|
|
+ result.detection = out_detections[i];
|
|
|
+ result.label = out_detections[i].cls;
|
|
|
+ result.score = out_detections[i].score;
|
|
|
+ results.push_back(result);
|
|
|
+ }
|
|
|
+ return true;
|
|
|
+ }
|
|
|
+ else{
|
|
|
+ std::cout<<"The out_detections size == 0 "<<std::endl;
|
|
|
+ return false;
|
|
|
+ }
|
|
|
+}
|
|
|
+
|
|
|
+bool sort_score(BBOX3D box1,BBOX3D box2)
|
|
|
+{
|
|
|
+ return (box1.score > box2.score);
|
|
|
+}
|
|
|
+
|
|
|
+//计算两个旋转矩形的IOU
|
|
|
+float calcIOU(cv::RotatedRect rect1, cv::RotatedRect rect2)
|
|
|
+{
|
|
|
+ float areaRect1 = rect1.size.width * rect1.size.height;
|
|
|
+ float areaRect2 = rect2.size.width * rect2.size.height;
|
|
|
+ vector<cv::Point2f> vertices;
|
|
|
+ int intersectionType = cv::rotatedRectangleIntersection(rect1, rect2, vertices);
|
|
|
+ if (vertices.size()==0)
|
|
|
+ return 0.0;
|
|
|
+ else{
|
|
|
+ vector<cv::Point2f> order_pts;
|
|
|
+ cv::convexHull(cv::Mat(vertices), order_pts, true);
|
|
|
+ double area = cv::contourArea(order_pts);
|
|
|
+ float inner = (float) (area / (areaRect1 + areaRect2 - area + 0.0001));
|
|
|
+ //排除小框完全在大框里面的case
|
|
|
+ float areaMin = (areaRect1 < areaRect2)?areaRect1:areaRect2;
|
|
|
+ float innerMin = (float)(area / (areaMin + 0.0001));
|
|
|
+ if(innerMin > smallinbig_threshold)
|
|
|
+ inner = innerMin;
|
|
|
+ return inner;
|
|
|
+ }
|
|
|
+}
|
|
|
+//计算两个点的欧式距离
|
|
|
+float calcdistance(cv::Point2f center1, cv::Point2f center2)
|
|
|
+{
|
|
|
+ float distance = sqrt((center1.x-center2.x)*(center1.x-center2.x)+
|
|
|
+ (center1.y-center2.y)*(center1.y-center2.y));
|
|
|
+ return distance;
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
+//nms
|
|
|
+void nms(std::vector<BBOX3D> &vec_boxs,float threshold,std::vector<BBOX3D> &results)
|
|
|
+{
|
|
|
+ std::sort(vec_boxs.begin(),vec_boxs.end(),sort_score);
|
|
|
+ while(vec_boxs.size() > 0)
|
|
|
+ {
|
|
|
+ results.push_back(vec_boxs[0]);
|
|
|
+ vec_boxs.erase(vec_boxs.begin());
|
|
|
+ for (auto it = vec_boxs.begin(); it != vec_boxs.end();)
|
|
|
+ {
|
|
|
+ float iou_value =calcIOU(results.back().box,(*it).box);
|
|
|
+ float distance_value = calcdistance(results.back().box.center,(*it).box.center);
|
|
|
+ if ((iou_value > threshold) || (distance_value<distance_threshold))
|
|
|
+ it = vec_boxs.erase(it);
|
|
|
+ else it++;
|
|
|
+ }
|
|
|
+
|
|
|
+// std::cout<<"results: "<<results.back().detection.at(0)<<" "<<results.back().detection.at(1)<<
|
|
|
+// " "<<results.back().detection.at(2)<<std::endl;
|
|
|
+
|
|
|
+ }
|
|
|
+}
|
|
|
+/////////////nms算法去除重叠交叉的框/////////////
|
|
|
|
|
|
|
|
|
//change lidarpoints to waymo type,x-->forward,y-->left
|
|
@@ -97,8 +249,6 @@ void GetLidarObj(std::vector<Box> &predResult,iv::lidar::objectarray & lidarobjv
|
|
|
|
|
|
Box result = predResult[idx];
|
|
|
|
|
|
- if (result.score < threshold) continue;
|
|
|
-
|
|
|
std::cout<<" The scores = "<<result.score<<std::endl;
|
|
|
|
|
|
lidarobj.set_tyaw(-result.theta);
|
|
@@ -179,6 +329,105 @@ void GetLidarObj(std::vector<Box> &predResult,iv::lidar::objectarray & lidarobjv
|
|
|
}
|
|
|
|
|
|
|
|
|
+
|
|
|
+void GetLidarObj_nms(std::vector<BBOX3D> &predResult,iv::lidar::objectarray & lidarobjvec)
|
|
|
+{
|
|
|
+ // givlog->verbose("OBJ","object size is %d",obj_size);
|
|
|
+ for(size_t idx = 0; idx < predResult.size(); idx++)
|
|
|
+ {
|
|
|
+ iv::lidar::lidarobject lidarobj;
|
|
|
+
|
|
|
+ Box result = predResult[idx].detection;
|
|
|
+
|
|
|
+ //std::cout<<" The scores = "<<result.score<<std::endl;
|
|
|
+
|
|
|
+ lidarobj.set_tyaw(-result.theta);
|
|
|
+
|
|
|
+ //std::cout<<" The theta = "<<result.theta<<std::endl;
|
|
|
+ //std::cout<<" The xyz = "<<result.cls<<" "<<result.w<<" "<<result.l<<" "<<result.h<<std::endl;
|
|
|
+
|
|
|
+ std::cout<<"obstacle id is: "<<idx<<std::endl;
|
|
|
+ std::cout<<"obstacle score is: "<<result.score<<std::endl;
|
|
|
+ std::cout<<"(x,y,z,dx,dy,dz,yaw,class)=("<<result.x<<","<<result.y<<","<<result.z<<","
|
|
|
+ <<result.w<<","<<result.l<<","<<result.h<<","<<result.theta<<","<<labels[result.cls]<<")"<<std::endl;
|
|
|
+
|
|
|
+ givlog->verbose("obstacle id is: %d",idx);
|
|
|
+ givlog->verbose("(x,y,z,dx,dy,dz,yaw,class)=(%f,%f,%f,%f,%f,%f,%f,%s)",result.x,result.y,result.z,
|
|
|
+ result.w,result.l,result.h,result.theta,labels[result.cls]);
|
|
|
+
|
|
|
+
|
|
|
+ iv::lidar::PointXYZ centroid;
|
|
|
+ iv::lidar::PointXYZ * _centroid;
|
|
|
+ centroid.set_x(-result.y);
|
|
|
+ centroid.set_y(result.x);
|
|
|
+ centroid.set_z(result.z);
|
|
|
+ _centroid = lidarobj.mutable_centroid();
|
|
|
+ _centroid->CopyFrom(centroid);
|
|
|
+
|
|
|
+ iv::lidar::PointXYZ min_point;
|
|
|
+ iv::lidar::PointXYZ * _min_point;
|
|
|
+ min_point.set_x(0);
|
|
|
+ min_point.set_y(0);
|
|
|
+ min_point.set_z(0);
|
|
|
+ _min_point = lidarobj.mutable_min_point();
|
|
|
+ _min_point->CopyFrom(min_point);
|
|
|
+
|
|
|
+ iv::lidar::PointXYZ max_point;
|
|
|
+ iv::lidar::PointXYZ * _max_point;
|
|
|
+ max_point.set_x(0);
|
|
|
+ max_point.set_y(0);
|
|
|
+ max_point.set_z(0);
|
|
|
+ _max_point = lidarobj.mutable_max_point();
|
|
|
+ _max_point->CopyFrom(max_point);
|
|
|
+
|
|
|
+ iv::lidar::PointXYZ position;
|
|
|
+ iv::lidar::PointXYZ * _position;
|
|
|
+ position.set_x(-result.y);
|
|
|
+ position.set_y(result.x);
|
|
|
+ position.set_z(result.z);
|
|
|
+ _position = lidarobj.mutable_position();
|
|
|
+ _position->CopyFrom(position);
|
|
|
+
|
|
|
+ lidarobj.set_mntype(result.cls);
|
|
|
+
|
|
|
+ lidarobj.set_score(result.score);
|
|
|
+ lidarobj.add_type_probs(result.score);
|
|
|
+
|
|
|
+ iv::lidar::PointXYZI point_cloud;
|
|
|
+ iv::lidar::PointXYZI * _point_cloud;
|
|
|
+
|
|
|
+ point_cloud.set_x(-result.y);
|
|
|
+ point_cloud.set_y(result.x);
|
|
|
+ point_cloud.set_z(result.z);
|
|
|
+
|
|
|
+ point_cloud.set_i(0);
|
|
|
+
|
|
|
+ _point_cloud = lidarobj.add_cloud();
|
|
|
+ _point_cloud->CopyFrom(point_cloud);
|
|
|
+
|
|
|
+ iv::lidar::Dimension ld;
|
|
|
+ iv::lidar::Dimension * pld;
|
|
|
+
|
|
|
+
|
|
|
+ ld.set_x(result.l);// w
|
|
|
+ ld.set_y(result.w);// l
|
|
|
+ ld.set_z(result.h);// h
|
|
|
+
|
|
|
+
|
|
|
+// ld.set_x(result.h);// w
|
|
|
+// ld.set_y(result.l);// l
|
|
|
+// ld.set_z(result.w);// h
|
|
|
+
|
|
|
+
|
|
|
+ pld = lidarobj.mutable_dimensions();
|
|
|
+ pld->CopyFrom(ld);
|
|
|
+ iv::lidar::lidarobject * po = lidarobjvec.add_obj();
|
|
|
+ po->CopyFrom(lidarobj);
|
|
|
+ }
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
void DectectOnePCD(const pcl::PointCloud<pcl::PointXYZI>::Ptr &pc_ptr)
|
|
|
{
|
|
|
|
|
@@ -187,14 +436,38 @@ void DectectOnePCD(const pcl::PointCloud<pcl::PointXYZI>::Ptr &pc_ptr)
|
|
|
int pointsnum = pc_ptr->width;
|
|
|
std::vector<Box> predResult;
|
|
|
|
|
|
+ QTime xTime;
|
|
|
+ xTime.start();
|
|
|
+
|
|
|
+
|
|
|
+ auto startTime0 = std::chrono::high_resolution_clock::now();
|
|
|
+
|
|
|
centerpoint->infer(points_array_ptr.get(),pointsnum,predResult);
|
|
|
|
|
|
+ auto endTime0 = std::chrono::high_resolution_clock::now();
|
|
|
+ double inferenceDuration = std::chrono::duration_cast<std::chrono::nanoseconds>(endTime0 - startTime0).count()/1000000.0;
|
|
|
+ std::cout<< "inferenceDuration Time: " << inferenceDuration << " ms"<< std::endl;
|
|
|
+
|
|
|
+ auto startTime1 = std::chrono::high_resolution_clock::now();
|
|
|
+ /////////////////增加nms算法进一步去除重叠交叉的框//////////////////
|
|
|
|
|
|
- std::cout<<"obj size is "<<predResult.size()<<std::endl;
|
|
|
+ std::vector<BBOX3D>results_rect;
|
|
|
+ GetRotatedRect(predResult,results_rect);
|
|
|
+ //std::cout<<"results_rect size: "<<results_rect.size()<<std::endl;
|
|
|
|
|
|
- // std::vector<iv::lidar::lidarobject> lidarobjvec;
|
|
|
+ std::vector<BBOX3D>results_bbox;
|
|
|
+ nms(results_rect,second_nms_threshold,results_bbox);
|
|
|
+ //std::cout<<"results_bbox size: "<<results_bbox.size()<<std::endl;
|
|
|
+ //std::cout<<"obj size is "<<predResult.size()<<std::endl;
|
|
|
+ /////////////////增加nms算法进一步去除重叠交叉的框//////////////////
|
|
|
+ auto endTime1 = std::chrono::high_resolution_clock::now();
|
|
|
+ double nmsDuration = std::chrono::duration_cast<std::chrono::nanoseconds>(endTime1 - startTime1).count()/1000000.0;
|
|
|
+ std::cout<< "nmsDuration Time: " << nmsDuration << " ms"<< std::endl;
|
|
|
+
|
|
|
+ //std::vector<iv::lidar::lidarobject> lidarobjvec;
|
|
|
iv::lidar::objectarray lidarobjvec;
|
|
|
- GetLidarObj(predResult,lidarobjvec);
|
|
|
+ //GetLidarObj(predResult,lidarobjvec);
|
|
|
+ GetLidarObj_nms(results_bbox,lidarobjvec);
|
|
|
|
|
|
double timex = pc_ptr->header.stamp;
|
|
|
timex = timex/1000.0;
|
|
@@ -319,7 +592,7 @@ void statethread()
|
|
|
if (nstate != nlaststate) {
|
|
|
switch (nstate) {
|
|
|
case 0:
|
|
|
- givlog->info("detection_lidar_pointpillar is ok");
|
|
|
+ givlog->info("detection_centerpoint is ok");
|
|
|
gfault->SetFaultState(0,0,"data is ok.");
|
|
|
break;
|
|
|
case 1:
|
|
@@ -356,20 +629,13 @@ int main(int argc, char** argv)
|
|
|
givlog = new iv::Ivlog("lidar_centerpoint");
|
|
|
gfault->SetFaultState(0,0,"centerpoint initialize. ");
|
|
|
|
|
|
-// samplesCommon::Args args;
|
|
|
-// bool argsOK = samplesCommon::parseArgs(args, argc, argv);
|
|
|
-// if (!argsOK)
|
|
|
-// {
|
|
|
-// sample::gLogError << "Invalid arguments" << std::endl;
|
|
|
-// printHelpInfo();
|
|
|
-// return EXIT_FAILURE;
|
|
|
-// }
|
|
|
-// if (args.help)
|
|
|
-// {
|
|
|
-// printHelpInfo();
|
|
|
-// return EXIT_SUCCESS;
|
|
|
-// }
|
|
|
+ snprintf(gstr_memname,255,"lidar_pc");
|
|
|
|
|
|
+ int nRtn = GetOptLong(argc,argv);
|
|
|
+ if(nRtn == 1) //show help,so exit.
|
|
|
+ {
|
|
|
+ return 0;
|
|
|
+ }
|
|
|
auto sampleTest = sample::gLogger.defineTest(gSampleName, argc, argv);
|
|
|
sample::gLogger.reportTestStart(sampleTest);
|
|
|
|
|
@@ -394,14 +660,22 @@ int main(int argc, char** argv)
|
|
|
params.rpnOnnxFilePath = xparam.GetParam("rpnOnnxFilePath","./rpn.onnx");
|
|
|
params.pfeSerializedEnginePath = xparam.GetParam("pfeEnginePath","./pfe.engine");
|
|
|
params.rpnSerializedEnginePath = xparam.GetParam("rpnEnginePath","./rpn.engine");
|
|
|
- params.savePath = "/home/nvidia/modularization/src/detection/CenterPoint-master/results";
|
|
|
- string filePath = "/home/nvidia/modularization/src/detection/CenterPoint-master/lidars";
|
|
|
+ params.savePath = "./results";
|
|
|
+ string filePath = "./lidars";
|
|
|
params.filePaths=glob(filePath + "/seq_*.bin");
|
|
|
- params.fp16 = true;
|
|
|
+ //params.fp16 = true;
|
|
|
+ params.fp16 = xparam.GetParam("fp16",true);
|
|
|
params.load_engine = xparam.GetParam("load_engine",true);
|
|
|
|
|
|
- //检测分数阈值
|
|
|
- threshold = xparam.GetParam("threshold",0.5);
|
|
|
+
|
|
|
+ //检测分数和nms的阈值
|
|
|
+ params.score_thr = xparam.GetParam("score_thr",0.5);
|
|
|
+ params.nms_thr = xparam.GetParam("nms_thr",0.5);
|
|
|
+
|
|
|
+ //第二次nms的阈值
|
|
|
+ smallinbig_threshold = xparam.GetParam("smallinbig_thr",0.8);
|
|
|
+ distance_threshold = xparam.GetParam("distance_thr",0.2);
|
|
|
+ second_nms_threshold = xparam.GetParam("second_nms_thr",0.5);
|
|
|
|
|
|
// Input Output Names, according to TASK_NUM
|
|
|
params.pfeInputTensorNames.push_back("input.1");
|
|
@@ -422,10 +696,6 @@ int main(int argc, char** argv)
|
|
|
params.batch_size = 1;
|
|
|
|
|
|
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
|
|
-
|
|
|
- // std::string savePath = "/home/wanghao/Desktop/projects/notebooks/centerpoint_output_cpp" ;
|
|
|
- //CenterPoint sample(params);
|
|
|
-
|
|
|
centerpoint = new CenterPoint(params);
|
|
|
|
|
|
sample::gLogInfo << "Building and running a GPU inference engine for CenterPoint" << std::endl;
|
|
@@ -442,7 +712,8 @@ int main(int argc, char** argv)
|
|
|
// }
|
|
|
|
|
|
|
|
|
- gpa = iv::modulecomm::RegisterRecv(&lidarname[0],ListenPointCloud);
|
|
|
+ //gpa = iv::modulecomm::RegisterRecv(&lidarname[0],ListenPointCloud);
|
|
|
+ gpa = iv::modulecomm::RegisterRecv(gstr_memname,ListenPointCloud);
|
|
|
gpdetect = iv::modulecomm::RegisterSend(&detectname[0], 10000000,1);
|
|
|
|
|
|
// gpthread = new std::thread(statethread);
|