Selaa lähdekoodia

修改测量为三次测量

zx 5 vuotta sitten
vanhempi
commit
37a5596546
3 muutettua tiedostoa jossa 125 lisäystä ja 39 poistoa
  1. 1 1
      locate/YoloDetector.cpp
  2. 35 19
      terminor/terminal_command_executor.cpp
  3. 89 19
      test/locate_sample.cpp

+ 1 - 1
locate/YoloDetector.cpp

@@ -106,7 +106,7 @@ Error_manager YoloDetector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
 
 			//LOG(WARNING) << "\tyolo minx:" << m_minx << ",maxx:" << m_maxx << ",miny:" << m_miny << ",maxy:" << m_maxy;
 			//LOG(WARNING) << "box " << i << " x:" << box.x << " ,y:" << box.y << " ,w:" << box.w << " ,h:" << box.h;
-			LOG(INFO) << "yolo box " << i << " x:" << box_y.x << " ,y:" << box_y.y << " ,w:" << box_y.w << " ,h:" << box_y.h;
+			//LOG(INFO) << "yolo box " << i << " x:" << box_y.x << " ,y:" << box_y.y << " ,w:" << box_y.w << " ,h:" << box_y.h;
 
 			boxes.push_back(box_y);
 			//����boxes

+ 35 - 19
terminor/terminal_command_executor.cpp

@@ -160,7 +160,7 @@ Error_manager Terminor_Command_Executor::execute_command(std::vector<Laser_base*
             mp_command_thread=0;
         }
     }
-    //第二步接受指令,保存输入参数,更新指令状态为,启动内部工作线程.返回SUCCESS
+    //第二步接受指令,保存输入参数,更新指令状态为TERMINOR_BUSY,启动内部工作线程.返回SUCCESS
     mp_laser_vector=lasers;
     mp_plc=plc;
     mp_locater=locater;
@@ -180,31 +180,47 @@ void Terminor_Command_Executor::thread_command_working(Terminor_Command_Executor
     {
         return ;
     }
-    //执行指令,阻塞直到指令执行完成或者异常结束
-    Error_manager code=terminor->scanning_measuring();
-    switch(code.get_error_code())
-    {
-        case SUCCESS:break;
-        case TERMINOR_LASER_TIMEOUT:
-        {
-            //雷达扫描超时,代表雷达故障,此时需要重置雷达模块
+    //执行指令,阻塞直到指令执行完成或者异常结束,此处如果失败,连续三次测量
+    Error_manager code;
+    int measure_times=0;
+    while(terminor->mb_force_quit==false) {
+        if (measure_times == 3)
+            break;
+        code = terminor->scanning_measuring();
+        switch (code.get_error_code()) {
+            case SUCCESS:
+                break;
+            case TERMINOR_LASER_TIMEOUT: {
+                //雷达扫描超时,代表雷达故障,此时需要重置雷达模块
+            }
+        }
+
+        if (code != SUCCESS ) {
+            if(measure_times==2)
+            {
+                LOG(ERROR) << " Measure times("<<measure_times<<")  failed : "<< code.to_string();
+            }
+            else
+            {
+                LOG(WARNING) << " Measure times("<<measure_times<<")  failed : "<< code.to_string();
+            }
+            measure_times++;
+        }
+        else {
+            LOG(INFO) << " Measure complete!!! times:"<<measure_times;
+            break;
         }
-    }
-    if(code!=SUCCESS)
-    {
-        LOG(ERROR)<<"Command execute failed : "<<code.to_string();
     }
     //根据结果执行上传任务
     code=terminor->post_measure_information();
     //更新终端状态为Ready状态
     terminor->m_terminor_statu=TERMINOR_READY;
-    if(code!=SUCCESS)
-    {
-        LOG(ERROR)<<"Command execute failed : "<<code.to_string();
+
+    if (code != SUCCESS) {
+        LOG(ERROR) << "Command measure execute failed : "<< code.to_string();
     }
-    else
-    {
-        LOG(INFO)<<"Command execute complete!!!";
+    else {
+        LOG(INFO) << "Command execute complete!!!";
     }
 }
 

+ 89 - 19
test/locate_sample.cpp

@@ -18,6 +18,55 @@ using google::protobuf::io::CodedInputStream;
 using google::protobuf::io::ZeroCopyOutputStream;
 using google::protobuf::io::CodedOutputStream;
 using google::protobuf::Message;
+#include <sys/stat.h>
+#include <dirent.h>
+
+void init_glog()
+{
+    FLAGS_max_log_size = 100;
+    FLAGS_logbufsecs = 0;
+    google::InitGoogleLogging("LidarMeasurement");
+    google::SetStderrLogging(google::INFO);
+    google::InstallFailureSignalHandler();
+    FLAGS_colorlogtostderr = true;        // Set log color
+    FLAGS_logbufsecs = 0;                // Set log output speed(s)
+    FLAGS_max_log_size = 1024;            // Set max log file size(GB)
+    FLAGS_stop_logging_if_full_disk = true;
+}
+void list_dir( const char * dir_name,std::vector<std::string>& files)
+{
+    if( 0 == dir_name )
+    {
+        std::cout<<" dir_name is null ! "<<std::endl;
+        return;
+    }
+
+    struct stat s;
+    lstat( dir_name , &s );
+    if( ! S_ISDIR( s.st_mode ) )
+    {
+        return;
+    }
+    struct dirent * filename;
+    DIR * dir;
+    dir = opendir( dir_name );
+    if( NULL == dir )
+    {
+        return;
+    }
+
+    int iName=0;
+    while( ( filename = readdir(dir) ) != NULL )
+    {
+        if( strcmp( filename->d_name , "." ) == 0 ||
+            strcmp( filename->d_name , "..") == 0)
+            continue;
+
+        char wholePath[128] = {0};
+        sprintf(wholePath, "%s", filename->d_name);
+        files.push_back(wholePath);
+    }
+}
 
 bool read_proto_param(std::string path, ::google::protobuf::Message& param)
 {
@@ -71,12 +120,12 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file)
 
 int main(int argc,char* argv[])
 {
-    std::string input_file="20191217-215217.txt";
+    init_glog();
+    std::string input_file="balck_suv";
     std::string out_path="./test";
     if(argc>=2)
     {
         input_file=argv[1];
-        input_file+=".txt";
     }
     if(argc>=3)
     {
@@ -96,27 +145,48 @@ int main(int argc,char* argv[])
     }
     Locate_task* task=new Locate_task();
 
-    std::string cloud_path="/home/zx/data/samples/src_txt/balck_suv/";
+    std::string cloud_path="/home/zx/data/samples/src_txt/";
     cloud_path+=input_file;
-    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud;
+    std::vector<std::string> files;
+    list_dir(cloud_path.c_str(),files);
+    int count=files.size();
+    int correct_size=0;
+    for(int i=0;i<files.size();++i) {
 
-    cloud=ReadTxtCloud(cloud_path);
-    std::cout<<"  input file: "<<cloud_path<<std::endl;
-    code=task->set_locate_cloud(cloud);
-    if(code!=SUCCESS)
-    {
-        LOG(ERROR)<<code.to_string();
-        return 0;
-    }
-    task->set_save_path(out_path);
-    code=locater->execute_task(task,5);
-    if(code==SUCCESS)
-    {
-        LOG(INFO)<<" LOCATE SUCCESS";
+        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud;
+        std::string t_file=cloud_path+"/"+files[i];
+        cloud = ReadTxtCloud(t_file);
+        std::cout << "  input file: " << t_file << std::endl;
+        code = task->set_locate_cloud(cloud);
+        if (code != SUCCESS) {
+            LOG(ERROR) << code.to_string();
+            return 0;
+        }
+        task->set_save_path(out_path);
+        code = locater->execute_task(task, 5);
+        if (code == SUCCESS) {
+            LOG(INFO) << " LOCATE SUCCESS";
+            correct_size++;
+        }
+        else {
+            LOG(ERROR) << code.to_string();
+            //移动文件
+            usleep(300);
+            std::string src="./test/cnn3d.txt";
+            std::string dst="./error/";
+            dst+=files[i];
+            std::string name="mv "+src+" "+dst;
+            const char *des_name=name.c_str();
+
+            system(des_name); //调用系统命令
+            usleep(200);
+
+        }
     }
-    else
+    if(count>0)
     {
-        LOG(ERROR)<<code.to_string();
+        std::cout<<std::endl<<"  acc : "<<correct_size<<"/"<<count<<
+        "    percent:"<<float(correct_size)/float(count)<<std::endl;
     }
     return 0;
 }