浏览代码

校验5->3度,轴距3000限制,放宽总loss单轮loss,wheelbase到3150,20200814

yct 4 年之前
父节点
当前提交
ca3a625be6

+ 1 - 1
locate/cnn3d_segmentation.cpp

@@ -394,7 +394,7 @@ Error_manager Cnn3d_segmentation::isRect(std::vector<cv::Point2f>& points)
         if(width<1400 || width >2000 || length >3300 ||length < 2200)
         {
             char description[255]={0};
-            sprintf(description,"width<1400 || width >2100 || length >3300 ||length < 2100 l:%.1f,w:%.1f",length,width);
+            sprintf(description,"width<1400 || width >2100 || wheel_base >3300 ||wheel_base < 2100 l:%.1f,w:%.1f",length,width);
             return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,NORMAL,description);
         }
 

+ 3 - 2
terminor/terminal_command_executor.cpp

@@ -482,8 +482,8 @@ Error_manager Terminor_Command_Executor::scanning_measuring() {
     float offset_width = fabs(dj_locate_information.locate_width - wj_locate_information.locate_width);
     float offset_wheel_base = fabs(
             dj_locate_information.locate_wheel_base - wj_locate_information.locate_wheel_base);
-    if (offset_x > 100 || offset_y > 150 || offset_angle > 5 || offset_wheel_base > 550 || offset_width > 250) {
-        LOG(WARNING) << "chekc failed. (offset x>100, y>150, angle>5, wheel_base>550, width>250): " << offset_x
+    if (offset_x > 100 || offset_y > 150 || offset_angle > 3 || offset_wheel_base > 550 || offset_width > 250) {
+        LOG(WARNING) << "chekc failed. (offset x>100, y>150, angle>3, wheel_base>550, width>250): " << offset_x
                      << " " << offset_y << " " << offset_angle << " " << offset_wheel_base << " " << offset_width;
         return Error_manager(TERMINOR_CHECK_RESULTS_ERROR, NORMAL, "check results failed ");
     }
@@ -503,6 +503,7 @@ Error_manager Terminor_Command_Executor::scanning_measuring() {
     float weight_wj = dj_distance / (dj_distance + wj_distance);
     m_measure_information.locate_wheel_base = weight_dj * dj_locate_information.locate_wheel_base +
                                               weight_wj * wj_locate_information.locate_wheel_base;
+    m_measure_information.locate_wheel_base=m_measure_information.locate_wheel_base>3000?3000:m_measure_information.locate_wheel_base;
     m_measure_information.locate_length = dj_locate_information.locate_length;
     m_measure_information.locate_width = wj_locate_information.locate_width;
     m_measure_information.locate_hight = dj_locate_information.locate_hight;

+ 4 - 4
verify/Verify_result.cpp

@@ -206,25 +206,25 @@ Error_manager Verify_result::verify(cv::RotatedRect rotate_rect,int terminal_id,
     {
         code|=LIMIT_BACK_ERROR;
     }
-    for(int i=0;i<4;++i)
+    /*for(int i=0;i<4;++i)
     {
         if(t_corners[i].y>corner_max_y)
         {
             code|=LIMIT_BACK_ERROR;
         }
-    }
+    }*/
     //前超界
     if(center_y>center_maxy)
     {
         code|=LIMIT_FRONT_ERROR;
     }
-    for(int i=0;i<4;++i)
+    /*for(int i=0;i<4;++i)
     {
         if(t_corners[i].y>corner_max_y)
         {
             code|=LIMIT_FRONT_ERROR;
         }
-    }
+    }*/
 
 
     ////第二步,根据id,检验左右栏杆

+ 6 - 6
wj_lidar/detect_wheel_ceres.cpp

@@ -364,7 +364,7 @@ bool detect_wheel_ceres::detect(std::vector<pcl::PointCloud<pcl::PointXYZ>> clou
         update_mat(map_rows, map_cols);
         Detect_result t_detect_result = detect_result;
         // 寻找最小loss值对应的初始旋转角
-        for (int i = -5; i < 6&&!stop_sign; i++)
+        for (int i = -5; i < 6&&!stop_sign; i+=2)
         {
             t_detect_result.theta = (-angle_x + i) * M_PI / 180.0;
             // printf("double x:%.3f  y: %.3f  wheel:%.3f  width:%.3f    theta : %.3f   front theta: %.3f\n",input_vars[0],input_vars[1],input_vars[3],input_vars[4],input_vars[2],input_vars[5]);
@@ -621,14 +621,14 @@ bool detect_wheel_ceres::Solve(Detect_result &detect_result, Loss_result &loss_r
     //检验
     // printf("loss: %.5f\n", loss);
     // printf("middle x:%.3f  y: %.3f  wheel:%.3f  width:%.3f    theta : %.3f   front theta: %.3f\n", variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);
-    if(loss>0.01)
+    if(loss>0.0115)
     {
 //        LOG(WARNING) <<"总loss过大 "<<loss;
         return false;
     }
-    if (detect_result.width < 1.350 || detect_result.width > 2.000 || detect_result.wheel_base > 3.000 || detect_result.wheel_base < 2.200)
+    if (detect_result.width < 1.350 || detect_result.width > 2.000 || detect_result.wheel_base > 3.150 || detect_result.wheel_base < 2.200)
     {
-//        LOG(WARNING) <<"宽度(1.35, 2.00) 轴距(2.20, 3.00): "<<detect_result.width<<", "<<detect_result.wheel_base;
+//        LOG(WARNING) <<"宽度(1.35, 2.00) 轴距(2.20, 3.15): "<<detect_result.width<<", "<<detect_result.wheel_base;
         return false;
     }
 
@@ -667,7 +667,7 @@ bool detect_wheel_ceres::Solve(Detect_result &detect_result, Loss_result &loss_r
             loss_result.rb_loss = loss;
         }
         // 判断每个轮子平均loss是否满足条件
-        double single_wheel_loss_threshold = 0.099;
+        double single_wheel_loss_threshold = 0.109;
         if(loss_result.lf_loss > single_wheel_loss_threshold || loss_result.rf_loss > single_wheel_loss_threshold  || loss_result.lb_loss > single_wheel_loss_threshold || loss_result.rb_loss > single_wheel_loss_threshold)
         {
 //            LOG(WARNING) <<"四轮loss过大"<<loss_result.lf_loss<<", "<<loss_result.rf_loss<<", "<<loss_result.lb_loss<<", "<<loss_result.rb_loss;
@@ -826,4 +826,4 @@ void detect_wheel_ceres::debug_img(Detect_result detect_result, Loss_result loss
         cv::convertScaleAbs(total_img * 255, cvted_img);
         cv::imwrite(img_filename, cvted_img);
     }
-}
+}

+ 3 - 3
wj_lidar/region_worker.cpp

@@ -134,7 +134,7 @@ void Region_worker::detect_loop(Region_worker *worker)
     if (worker->m_detector == 0)
         return;
     // 2.检测与更新循环
-    while (!worker->m_cond_exit.WaitFor(200))
+    while (!worker->m_cond_exit.WaitFor(100))
     {
 //        LOG(INFO) << "worker detect loop";
         // 检查当前状态
@@ -196,8 +196,8 @@ void Region_worker::detect_loop(Region_worker *worker)
             // 写入plc,加入写入频率限制
             int duration = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::steady_clock::now() - worker->m_update_plc_time).count();
             Plc_data *p = Plc_data::get_instance();
-            // 写入间隔必须超过500ms,当前状态不同于上次写入状态,且该状态已连续读到三次
-            if (p!=0 && duration > 500 && ((worker->m_last_sent_code != worker->m_last_read_code) || worker->m_last_border_status != border_status) && worker->m_read_code_count > 3)
+            // 写入间隔必须超过200ms,当前状态不同于上次写入状态,且该状态已连续读到三次
+            if (p!=0 && duration > 200 && ((worker->m_last_sent_code != worker->m_last_read_code) || worker->m_last_border_status != border_status) && worker->m_read_code_count > 3)
             {
                 worker->m_last_sent_code = worker->m_last_read_code;
 		        worker->m_last_border_status = border_status;