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