Pārlūkot izejas kodu

change export_onnx.py

liyupeng 7 mēneši atpakaļ
vecāks
revīzija
7dcac8b65f

+ 2 - 0
src/detection/CenterPoint-master/CenterPoint.pro

@@ -123,6 +123,7 @@ else {
 
 
 LIBS += -L/usr/local/cuda-10.2/targets/aarch64-linux/lib
+LIBS += -L/usr/local/cuda/lib64
 
 LIBS += -lcudart -lcufft -lyaml-cpp
 
@@ -135,6 +136,7 @@ LIBS +=  -lnvinfer -lnvonnxparser -lnvcaffe_parser
 unix:INCLUDEPATH += /usr/include/eigen3
 unix:INCLUDEPATH += /usr/include/pcl-1.7
 unix:INCLUDEPATH += /usr/include/pcl-1.8
+unix:INCLUDEPATH += /usr/include/pcl-1.10
 
 !include(../../../include/common.pri ) {
     error( "Couldn't find the common.pri file!" )

+ 11 - 6
src/detection/CenterPoint-master/detection_centerpoint.xml

@@ -1,10 +1,15 @@
 <xml>	
 	<node name="detection_centerpoint.xml">
-		<param name="pfeOnnxFilePath" value="/media/nvidia/Lexar/onnx/pfe_self2.onnx" />
-		<param name="rpnOnnxFilePath" value="/media/nvidia/Lexar/onnx/rpn_self2.onnx" />
-		<param name="pfeEnginePath" value="/media/nvidia/Lexar/onnx/pfe_fp_self2.engine" />
-		<param name="rpnEnginePath" value="/media/nvidia/Lexar/onnx/rpn_fp_self2.engine" />
-                <param name="threshold" value="0.5" />
-		<param name="load_engine" value="true" />  #if does not have engine,value=false,then use onnx get engine
+		<param name="pfeOnnxFilePath" value="./model/pfe_self_7class.onnx" />
+		<param name="rpnOnnxFilePath" value="./model/rpn_self_7class.onnx" />
+		<param name="pfeEnginePath" value="./model/pfe_self_7class_fp32.engine" />
+		<param name="rpnEnginePath" value="./model/rpn_self_7classs_fp32.engine" />
+                <param name="score_thr" value="0.5" />
+                <param name="nms_thr" value="0.5" />
+                <param name="smallinbig_thr" value="0.8" />  #remove overlap box,small boxes in big boxes
+                <param name="distance_thr" value="0.2" />    #distance between the center points of the two boxes 
+                <param name="second_nms_thr" value="0.5" />  #do the second nms
+                <param name="fp16" value="true" />    #when you want  to do inference on fp16 mode, this config is only valid when you create engine from onnx files
+		<param name="load_engine" value="true" />    #if it does not have engine,value=false,then use onnx get engine
 	</node>
 </xml>

+ 4 - 0
src/detection/CenterPoint-master/include/centerpoint.h

@@ -46,6 +46,10 @@ struct Params{
     bool int8 = false;
     bool load_engine = false;
     int batch_size = 1;
+
+    //threshold
+    float score_thr;
+    float nms_thr;
 };
 
 class CenterPoint

+ 7 - 8
src/detection/CenterPoint-master/include/config.h

@@ -1,12 +1,12 @@
 #ifndef __CENTERNET_CONFIG_H__
 #define __CENTERNET_CONFIG_H__
 
-// ========================================WAYMO CENTERPOINT CONFIG======================================== 
+// ========================================WAYMO CENTERPOINT CONFIG========================================
 // point size
 #define MAX_POINTS 220000
 #define POINT_DIM 5
 
-// pillar size 
+// pillar size
 #define X_STEP 0.32f
 #define Y_STEP 0.32f
 #define X_MIN -74.88f
@@ -41,7 +41,7 @@
 const int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;
 
 // OUT_SIZE_FACTOR * OUTPUT_H  * Y_STEP = Y_MAX - Y_MIN
-#define OUT_SIZE_FACTOR 1.0f    
+#define OUT_SIZE_FACTOR 1.0f
 
 #define TASK_NUM 1
 #define REG_CHANNEL 2
@@ -50,8 +50,8 @@ const int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;
 // #define VEL_CHANNEL 2 //don't defined in waymo
 #define DIM_CHANNEL 3
 
-// spatial output size of rpn 
-#define OUTPUT_H 468  
+// spatial output size of rpn
+#define OUTPUT_H 468
 #define OUTPUT_W 468
 #endif
 
@@ -60,9 +60,9 @@ const int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;
 
 
 
-// ========================================NUSCENES CENTERPOINT CONFIG======================================== 
+// ========================================NUSCENES CENTERPOINT CONFIG========================================
 
-// // pillar size 
+// // pillar size
 // #define X_STEP 0.2f
 // #define Y_STEP 0.2f
 // #define X_MIN -51.2f
@@ -109,4 +109,3 @@ const int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;
 
 
 
-

+ 4 - 2
src/detection/CenterPoint-master/include/postprocess.h

@@ -51,7 +51,9 @@ void postprocessGPU(samplesCommon::BufferManager * buffers,
                                                  int* host_score_indexs,
                                                  long* host_keep_data,
                                                  float* host_boxes,
-                                                 int* host_label);
-void postprocess(samplesCommon::BufferManager * buffers, std::vector<Box>& predResult);
+                                                 int* host_label,
+                                                 float score_threshold,
+                                                 float nms_threshold);
+void postprocess(samplesCommon::BufferManager * buffers, std::vector<Box>& predResult,float score_threshold,float nms_threshold);
 
 #endif

+ 1 - 1
src/detection/CenterPoint-master/src/centerpoint.cpp

@@ -290,7 +290,7 @@ bool CenterPoint::infer(float* lidarpoints,int pointsnum,std::vector<Box>& predR
                                             host_score_idx_,
                                             host_keep_data_,
                                             host_boxes_,
-                                            host_label_);
+                                            host_label_,mParams.score_thr,mParams.nms_thr);
     cudaEventRecord(stop);
     cudaEventSynchronize(stop);
     cudaEventElapsedTime(&post_time, start, stop);

+ 302 - 31
src/detection/CenterPoint-master/src/main.cpp

@@ -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);

+ 12 - 8
src/detection/CenterPoint-master/src/postprocess.cpp

@@ -100,7 +100,7 @@ inline float IoUBev(Box& boxA, Box& boxB){
     return sInter/sUnion;
 }
 
-void AlignedNMSBev(std::vector<Box>& predBoxs){
+void AlignedNMSBev(std::vector<Box>& predBoxs,float nms_threshold){
     
     if(predBoxs.size() == 0)
         return;
@@ -136,14 +136,16 @@ void AlignedNMSBev(std::vector<Box>& predBoxs){
         for(auto boxIdx2 = boxIdx1+1; boxIdx2 < boxSize; boxIdx2++){
             if(predBoxs[boxIdx2].isDrop == true)
                 continue;
-            if(IoUBev(predBoxs[boxIdx1], predBoxs[boxIdx2]) > NMS_THREAHOLD)
+            if(IoUBev(predBoxs[boxIdx1], predBoxs[boxIdx2]) > nms_threshold)
                 predBoxs[boxIdx2].isDrop = true;
         } 
         if (!predBoxs[boxIdx1].isDrop) numBoxValid ++;
     }
 }
 
-void postprocess(samplesCommon::BufferManager * buffers, std::vector<Box>& predResult){
+void postprocess(samplesCommon::BufferManager * buffers, std::vector<Box>& predResult,
+                 float score_threshold,float nms_threshold)
+{
 
 
 // #define REG_CHANNEL 2
@@ -174,7 +176,7 @@ for (int taskIdx=0;taskIdx < TASK_NUM;taskIdx++){
         for(size_t yIdx=0; yIdx < OUTPUT_H; yIdx++){
             for(size_t xIdx=0; xIdx < OUTPUT_W; xIdx++){
                 auto idx = yIdx* OUTPUT_W + xIdx;
-                if(score[idx] < SCORE_THREAHOLD)
+                if(score[idx] < score_threshold)
                     continue;
                 
                 float x = (xIdx + reg[0*OUTPUT_H*OUTPUT_W + idx])*OUT_SIZE_FACTOR*X_STEP + X_MIN;
@@ -205,7 +207,7 @@ for (int taskIdx=0;taskIdx < TASK_NUM;taskIdx++){
         }
         std::cout << " Num boxes before nms " << cnt << "\n";
 
-        AlignedNMSBev(predBoxs);
+        AlignedNMSBev(predBoxs,nms_threshold);
         for(auto idx =0; idx < predBoxs.size(); idx++){
             if(!predBoxs[idx].isDrop)
                 predResult.push_back(predBoxs[idx]);
@@ -227,7 +229,9 @@ void postprocessGPU(samplesCommon::BufferManager * buffers,
                                                  int* host_score_indexs,
                                                  long* host_keep_data,
                                                  float* host_boxes,
-                                                 int* host_label
+                                                 int* host_label,
+                                                 float score_threshold,
+                                                 float nms_threshold
                                                  )
 {
 
@@ -244,7 +248,7 @@ void postprocessGPU(samplesCommon::BufferManager * buffers,
 
         // cudaStream_t stream;
         // GPU_CHECK(cudaStreamCreate(&stream));
-        int boxSize = _find_valid_score_num( score, SCORE_THREAHOLD, OUTPUT_H , OUTPUT_W);
+        int boxSize = _find_valid_score_num( score, score_threshold, OUTPUT_H , OUTPUT_W);
         std::cout << " Num boxes before " << boxSize <<"\n";
 
         _sort_by_key(score, dev_score_indexs, OUTPUT_W * OUTPUT_H);
@@ -253,7 +257,7 @@ void postprocessGPU(samplesCommon::BufferManager * buffers,
         // int boxSizeAft = raw_nms_gpu(reg,  height, dim , rot, dev_score_indexs, 
         //                                                 host_keep_data, boxSize,  NMS_THREAHOLD);
         int boxSizeAft = _raw_nms_gpu(reg,  height, dim , rot, dev_score_indexs, 
-                                                     host_keep_data, mask_cpu, remv_cpu,  boxSize,  NMS_THREAHOLD);
+                                                     host_keep_data, mask_cpu, remv_cpu,  boxSize,  nms_threshold);
 
 
 

+ 22 - 15
src/detection/CenterPoint-master/tools/export_onnx.py

@@ -22,6 +22,8 @@ import matplotlib.cm as cm
 import subprocess
 import cv2,pdb
 import argparse
+#from generate_calib_data import pad_voxel,convert2scatter
+
 
 def parse_args():
     parser = argparse.ArgumentParser(description="export a detector")
@@ -33,11 +35,6 @@ def parse_args():
     args = parser.parse_args()
     return args
 
-args  = parse_args()
-
-
-
-
 def example_to_device(example, device=None, non_blocking=False) -> dict:
     assert device is not None
     example_torch = {}
@@ -78,9 +75,18 @@ class PointPillars(nn.Module):
             preds[task]['dim'] = torch.exp(preds[task]['dim'])
             scores, labels = torch.max(hm_preds, dim=1)
             preds[task]["hm"] = (scores, labels)
-        return preds
+        #######源代码错误,无法导出onnx,修改
+        #return preds
+        return (preds[0]["reg"],preds[0]["height"],preds[0]["dim"],preds[0]["rot"],preds[0]["hm"][0],preds[0]["hm"][1])
+
+#args  = parse_args()
+
+config = "./waymo_centerpoint_pp_two_pfn_stride1_3x_self.py"
+ckpt =  "/home/vanessa/lqx/PycharmProjects/CenterPoint-master/work_dirs/waymo_centerpoint_pp_two_pfn_stride1_3x_self_7class_36/epoch_36.pth"
+pfe_save_path = "./pfe_self_7class.onnx"
+rpn_save_path = "./rpn_self_7class.onnx"
 
-cfg = Config.fromfile(args.config)
+cfg = Config.fromfile(config)
 cfg.EXPORT_ONNX = True
 model = build_detector(cfg.model, train_cfg=None, test_cfg=cfg.test_cfg)
 dataset = build_dataset(cfg.data.val)
@@ -93,7 +99,7 @@ data_loader = DataLoader(
     collate_fn=collate_kitti,
     pin_memory=False,
 )
-checkpoint = load_checkpoint(model, args.ckpt,map_location="cpu")
+checkpoint = load_checkpoint(model, ckpt,map_location="cpu")
 model.eval()
 model = model.cuda()
 gpu_device = torch.device("cuda")
@@ -106,20 +112,21 @@ with torch.no_grad():
     example["voxels"] = torch.zeros((example["voxels"].shape[0],example["voxels"].shape[1],10),dtype=torch.float32,device=gpu_device)
     example.pop("points")
     example["shape"] = torch.tensor(example["shape"], dtype=torch.int32, device=gpu_device)
-    pfe_inputs = torch.empty(args.max_pillars,20,10)
+    pfe_inputs = torch.empty(cfg.max_pillars,20,10)
     pfe_inputs[:example["voxels"].shape[0]] = example['voxels']
-
-    torch.onnx.export(model.reader,(pfe_inputs.cuda(),example["num_points"],example["coordinates"]), args.pfe_save_path,opset_version=11)
-
+    torch.onnx.export(model.reader,(pfe_inputs.cuda(),example["num_points"],example["coordinates"]), pfe_save_path,opset_version=11)
     rpn_input  = torch.randn((1,64,468,468),dtype=torch.float32,device=gpu_device)
-
     # getting errors with opset_version 11 , changed with 10
-    torch.onnx.export(pp_model, (rpn_input), args.rpn_save_path ,opset_version=10)
+    #preds = pp_model.forward(rpn_input)
 
+    torch.onnx.export(pp_model, (rpn_input), rpn_save_path ,opset_version=10)
 
 
 
 
+
+
+"""
 points = data_batch['points'][:, 1:4].cpu().numpy()
 MAX_PILLARS = 32000
 save_path = "/mnt/data/waymo_opensets/val/calibrations/"
@@ -135,7 +142,7 @@ with torch.no_grad():
         pfe_inputs = pfe_inputs.cpu().numpy()
         pfe_inputs.tofile(save_path + token[:-4] + "_pfe_input.npy")
         scatter_images.tofile(save_path + token[:-4] + "_rpn_input.npy")
-
+"""
 
 
 

+ 266 - 0
src/detection/CenterPoint-master/tools/waymo_centerpoint_pp_two_pfn_stride1_3x_self.py

@@ -0,0 +1,266 @@
+import itertools
+import logging
+from det3d.utils.config_tool import get_downsample_factor
+
+
+ROOT_PATH = '/media/vanessa/Elements-lqx/AutoPilot/lidardata_pkl/'
+# ROOT_PATH = "/mnt/data/waymo_opensets/val_sub0.1/"
+
+total_epochs = 8
+
+SAMPLES_PER_GPU = 2
+WORKERS_PER_GPU = 8
+MIX_PREC = True,
+EXPORT_ONNX = True
+NMS_IOU_THRESHOLD = 0.4
+SCORE_THRESHOLD = 0.1
+
+# key params
+max_pillars = 32000
+max_points_in_voxel = 20
+bev_h = 468
+bev_w = 468
+feature_num = 10
+pfe_output_dim = 64
+x_step = 0.32
+y_step = 0.32
+x_range = 74.88
+y_range = 74.88
+
+"""
+tasks = [
+    dict(num_class=5, class_names=['car', 'truck', 'alien_vehicle',
+                         'non_motor_vehicle','pedestrain']),
+]
+"""
+
+
+tasks = [
+    dict(num_class=7, class_names=['car', 'bus', 'truck', 'alien_vehicle',
+                         'non_motor_vehicle','pedestrain','cyclist']),
+]
+
+
+class_names = list(itertools.chain(*[t["class_names"] for t in tasks]))
+
+# training and testing settings
+target_assigner = dict(
+    tasks=tasks,
+)
+
+# model settings
+model = dict(
+    type="PointPillars",
+    pretrained=None,
+    reader=dict(
+        type="PillarFeatureNet",
+        num_filters=[64, 64],
+        num_input_features=5,
+        with_distance=False,
+        voxel_size=(x_step, y_step, 6.0),
+        pc_range=(-x_range, -y_range, -2, x_range, y_range, 4.0),
+        export_onnx = EXPORT_ONNX,
+    ),
+    backbone=dict(type="PointPillarsScatter", ds_factor=1),
+    neck=dict(
+        type="RPN",
+        layer_nums=[3, 5, 5],
+        ds_layer_strides=[1, 2, 2],
+        ds_num_filters=[64, 128, 256],
+        us_layer_strides=[1, 2, 4],
+        us_num_filters=[128, 128, 128],
+        num_input_features=pfe_output_dim,
+        logger=logging.getLogger("RPN"),
+    ),
+    bbox_head=dict(
+        type="CenterHead",
+        in_channels=128*3,
+        tasks=tasks,
+        dataset='waymo',
+        weight=2,
+        code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],
+        # common_heads={'reg': (2, 2), 'height': (1, 2), 'dim':(3, 2), 'rot':(2, 2)}, # (output_channel, num_conv)
+        common_heads={'reg': (2, 2), 'height': (1, 2), 'dim':(3, 2), 'rot':(2, 2)}, # (output_channel, num_conv)
+
+    ),
+)
+
+
+assigner = dict(
+    target_assigner=target_assigner,
+    out_size_factor=get_downsample_factor(model),
+    dense_reg=1,
+    gaussian_overlap=0.1,
+    max_objs=500,
+    min_radius=2,
+)
+
+
+train_cfg = dict(assigner=assigner)
+
+test_cfg = dict(
+    post_center_limit_range=[-80, -80, -10.0, 80, 80, 10.0],
+    nms=dict(
+        nms_pre_max_size=4096,
+        nms_post_max_size=500,
+        nms_iou_threshold=NMS_IOU_THRESHOLD,
+    ),
+    score_threshold=SCORE_THRESHOLD,
+    pc_range= [-x_range, -y_range],  #[-74.88, -74.88],
+    out_size_factor=get_downsample_factor(model),
+    voxel_size=  [x_step, y_step] # [0.32, 0.32]
+)
+
+
+# dataset settings
+dataset_type = "WaymoDataset"
+nsweeps = 1
+data_root = ROOT_PATH
+
+db_sampler = dict(
+    type="GT-AUG",
+    enable=False,
+    db_info_path="/media/vanessa/Elements-lqx/AutoPilot/lidardata_pkl/dbinfos_train_1sweeps_withvelo.pkl",
+    sample_groups=[
+        dict(car=15),
+        dict(bus=10),
+        dict(truck=10),
+        dict(alien_vehicle=10),
+        dict(non_motor_vehicle=10),
+        dict(pedestrain=10),
+        dict(cyclist=10)
+
+    ],
+    db_prep_steps=[
+        dict(
+            filter_by_min_num_points=dict(
+                car=5,
+                bus=5,
+                truck=5,
+                alien_vehicle=5,
+                non_motor_vehicle=5,
+                pedestrain=5,
+                cyclist=5
+            )
+        ),
+        dict(filter_by_difficulty=[-1],),
+    ],
+    global_random_rotation_range_per_object=[0, 0],
+    rate=1.0,
+) 
+
+train_preprocessor = dict(
+    mode="train",
+    shuffle_points=True,
+    global_rot_noise=[-0.78539816, 0.78539816],
+    global_scale_noise=[0.95, 1.05],
+    db_sampler=db_sampler,
+    class_names=class_names,
+)
+
+val_preprocessor = dict(
+    mode="val",
+    shuffle_points=False,
+)
+
+voxel_generator = dict(
+    range=   [-x_range, -y_range, -2, x_range, y_range, 4.0], #[-74.88, -74.88, -2, 74.88, 74.88, 4.0],
+    voxel_size=  [x_step, y_step, 6.0], # [0.32, 0.32, 6.0],
+    max_points_in_voxel=  max_points_in_voxel, # 20,
+    max_voxel_num= [32000, 60000], # we only use non-empty voxels. this will be much smaller than max_voxel_num
+)
+
+train_pipeline = [
+    dict(type="LoadPointCloudFromFile", dataset=dataset_type),
+    dict(type="LoadPointCloudAnnotations", with_bbox=True),
+    dict(type="Preprocess", cfg=train_preprocessor),
+    dict(type="Voxelization", cfg=voxel_generator),
+    dict(type="AssignLabel", cfg=train_cfg["assigner"]),
+    dict(type="Reformat"),
+]
+test_pipeline = [
+    dict(type="LoadPointCloudFromFile", dataset=dataset_type),
+    dict(type="LoadPointCloudAnnotations", with_bbox=True),
+    dict(type="Preprocess", cfg=val_preprocessor),
+    dict(type="Voxelization", cfg=voxel_generator),
+    dict(type="AssignLabel", cfg=train_cfg["assigner"]),
+    dict(type="Reformat"),
+]
+
+train_anno = ROOT_PATH + "infos_train_01sweeps_filter_zero_gt.pkl"
+val_anno = ROOT_PATH + "infos_train_01sweeps_filter_zero_gt.pkl"
+test_anno = None
+
+data = dict(
+    samples_per_gpu=SAMPLES_PER_GPU,
+    workers_per_gpu=WORKERS_PER_GPU,
+    mix_prec = MIX_PREC, 
+    train=dict(
+        type=dataset_type,
+        root_path=data_root,
+        info_path=train_anno,
+        ann_file=train_anno,
+        nsweeps=nsweeps,
+        class_names=class_names,
+        pipeline=train_pipeline,
+    ),
+    val=dict(
+        type=dataset_type,
+        root_path=data_root,
+        info_path=val_anno,
+        test_mode=True,
+        ann_file=val_anno,
+        nsweeps=nsweeps,
+        class_names=class_names,
+        pipeline=test_pipeline,
+    ),
+    test=dict(
+        type=dataset_type,
+        root_path=data_root,
+        info_path=test_anno,
+        ann_file=test_anno,
+        nsweeps=nsweeps,
+        class_names=class_names,
+        pipeline=test_pipeline,
+    ),
+)
+
+
+
+optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2))
+
+# optimizer
+optimizer = dict(
+    type="adam", amsgrad=0.0, wd=0.01, fixed_wd=True, moving_average=False,
+)
+lr_config = dict(
+    type="one_cycle", lr_max=0.003, moms=[0.95, 0.85], div_factor=10.0, pct_start=0.4,
+)
+
+checkpoint_config = dict(interval=1)
+# yapf:disable
+log_config = dict(
+    interval=5,
+    hooks=[
+        dict(type="TextLoggerHook"),
+        # dict(type='TensorboardLoggerHook')
+    ],
+)
+# yapf:enable
+# runtime settings
+device_ids = range(8)
+dist_params = dict(backend="nccl", init_method="env://")
+log_level = "INFO"
+work_dir = './work_dirs/{}/'.format(__file__[__file__.rfind('/') + 1:-3])
+load_from = None 
+resume_from = None  
+workflow = [('train', 1)]
+
+
+
+
+
+
+
+
+