|
@@ -316,6 +316,7 @@ Ground_region::~Ground_region()
|
|
|
|
|
|
Error_manager Ground_region::init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model)
|
|
|
{
|
|
|
+ m_range_status_last = 0;
|
|
|
Region_status_checker::get_instance_references().Region_status_checker_init();
|
|
|
m_region = region;
|
|
|
m_detector = new detect_wheel_ceres3d(left_model,right_model);
|
|
@@ -628,6 +629,7 @@ Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, d
|
|
|
|
|
|
int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double plate_cx, double plate_cy, double theta)
|
|
|
{
|
|
|
+ // LOG(WARNING) << m_range_status_last;
|
|
|
if(cloud->size() <= 0)
|
|
|
return Range_status::Range_correct;
|
|
|
int res = Range_status::Range_correct;
|
|
@@ -645,14 +647,40 @@ int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
|
|
|
}
|
|
|
pcl::PointXYZ min_p, max_p;
|
|
|
pcl::getMinMax3D(t_cloud, min_p, max_p);
|
|
|
+
|
|
|
+#ifndef ANTI_SHAKE
|
|
|
// 判断左右超界情况
|
|
|
if(min_p.x < m_region.border_minx())
|
|
|
res |= Range_status::Range_left;
|
|
|
if(max_p.x > m_region.border_maxx())
|
|
|
res |= Range_status::Range_right;
|
|
|
-
|
|
|
// LOG_IF(WARNING, m_region.region_id() == 4)<< "border minmax x: "<< min_p.x<<", "<<max_p.x<<", res: "<<res;
|
|
|
return res;
|
|
|
+#else
|
|
|
+ if(min_p.x < m_region.border_minx()-0.005)
|
|
|
+ {
|
|
|
+ m_range_status_last |= Range_status::Range_left;
|
|
|
+ }
|
|
|
+ else if(min_p.x > m_region.border_minx()+0.005)
|
|
|
+ {
|
|
|
+ int t = Range_status::Range_left;
|
|
|
+ m_range_status_last &= (~t);
|
|
|
+ }
|
|
|
+ //else m_range_status_last no change
|
|
|
+
|
|
|
+ if(max_p.x > m_region.border_maxx()+0.005)
|
|
|
+ {
|
|
|
+ m_range_status_last |= Range_status::Range_right;
|
|
|
+ }
|
|
|
+ else if(max_p.x < m_region.border_maxx()-0.005)
|
|
|
+ {
|
|
|
+ int t = Range_status::Range_right;
|
|
|
+ m_range_status_last &= (~t);
|
|
|
+ }
|
|
|
+ //else m_range_status_last no change
|
|
|
+
|
|
|
+ return m_range_status_last;
|
|
|
+#endif //ANTI_SHAKE
|
|
|
}
|
|
|
|
|
|
int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, Common_data::Car_wheel_information measure_result, double plate_cx, double plate_cy, double theta)
|
|
@@ -667,8 +695,9 @@ int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
|
|
|
double theta_rad = theta * M_PI / 180.0;
|
|
|
car_uniform_center.x() = car_center.x() * cos(theta_rad) - car_center.y() * sin(theta_rad);
|
|
|
car_uniform_center.y() = car_center.x() * sin(theta_rad) + car_center.y() * cos(theta_rad);
|
|
|
- // 车位位于y负方向,判断后轮超界情况
|
|
|
|
|
|
+#ifndef ANTI_SHAKE
|
|
|
+ // 车位位于y负方向,判断后轮超界情况
|
|
|
//yct old program 20221101
|
|
|
// double rear_wheel_y = car_uniform_center.y() + m_region.plc_offsety() - 0.5 * measure_result.car_wheel_base;
|
|
|
// if(rear_wheel_y < m_region.plc_border_miny())
|
|
@@ -725,24 +754,6 @@ int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
|
|
|
res |= Range_status::Range_angle_clock;
|
|
|
}
|
|
|
|
|
|
-// if (t_terminal_id == 3)
|
|
|
-// {
|
|
|
-//
|
|
|
-// LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx t_terminal_id = " << t_terminal_id << " ";
|
|
|
-//
|
|
|
-// LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx m_region.plc_offset_degree() = " << m_region.plc_offset_degree() << " ";
|
|
|
-//
|
|
|
-//
|
|
|
-// LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx t_dtheta = " << t_dtheta << " ";
|
|
|
-// LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx turnplate_angle_min = " << System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min() << " ";
|
|
|
-// LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx turnplate_angle_max = " << System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max() << " ";
|
|
|
-//
|
|
|
-// }
|
|
|
-
|
|
|
-
|
|
|
-
|
|
|
-
|
|
|
-
|
|
|
// // 判断车辆前轮角回正情况
|
|
|
// if (fabs(measure_result.car_front_theta) > 8.0)
|
|
|
// {
|
|
@@ -750,6 +761,88 @@ int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
|
|
|
// }
|
|
|
res |= outOfRangeDetection(cloud, plate_cx, plate_cy, theta);
|
|
|
return res;
|
|
|
+#else
|
|
|
+ // LOG(WARNING) << m_range_status_last;
|
|
|
+ // 车位位于y负方向,判断后轮超界情况
|
|
|
+ double t_center_y = 0.0 - (car_uniform_center.y() + m_region.plc_offsety()); // 汽车中心y, 参照plc坐标,并且进行偏移, 绝对值。结果大约为 5~6左右
|
|
|
+ if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_maxy()-0.005 &&
|
|
|
+ t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_miny()-0.005 )
|
|
|
+ {
|
|
|
+ int t = Range_status::Range_back;
|
|
|
+ m_range_status_last &= (~t);
|
|
|
+ }
|
|
|
+ else if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) > m_region.plc_border_maxy()+0.005 ||
|
|
|
+ t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) > m_region.plc_border_miny()+0.005 )
|
|
|
+ {
|
|
|
+ m_range_status_last |= Range_status::Range_back;
|
|
|
+ }
|
|
|
+ //else m_range_status_last no change
|
|
|
+ // LOG(WARNING) << m_range_status_last;
|
|
|
+
|
|
|
+ // 判断车辆宽度超界情况
|
|
|
+ if (measure_result.car_wheel_width < m_region.car_min_width()-0.005 ||
|
|
|
+ measure_result.car_wheel_width > m_region.car_max_width()+0.005)
|
|
|
+ {
|
|
|
+ m_range_status_last |= Range_status::Range_car_width;
|
|
|
+ }
|
|
|
+ else if (measure_result.car_wheel_width > m_region.car_min_width()+0.005 &&
|
|
|
+ measure_result.car_wheel_width < m_region.car_max_width()-0.005)
|
|
|
+ {
|
|
|
+ int t = Range_status::Range_car_width;
|
|
|
+ m_range_status_last &= (~t);
|
|
|
+ }
|
|
|
+ //else m_range_status_last no change
|
|
|
+ // LOG(WARNING) << m_range_status_last;
|
|
|
+
|
|
|
+ // 判断车辆轴距超界情况
|
|
|
+ if (measure_result.car_wheel_base < m_region.car_min_wheelbase()-0.005 ||
|
|
|
+ measure_result.car_wheel_base > m_region.car_max_wheelbase()+0.005)
|
|
|
+ {
|
|
|
+ res |= Range_status::Range_car_wheelbase;
|
|
|
+ }
|
|
|
+ else if (measure_result.car_wheel_base > m_region.car_min_wheelbase()+0.005 ||
|
|
|
+ measure_result.car_wheel_base < m_region.car_max_wheelbase()-0.005)
|
|
|
+ {
|
|
|
+ int t = Range_status::Range_car_wheelbase;
|
|
|
+ m_range_status_last &= (~t);
|
|
|
+ }
|
|
|
+ //else m_range_status_last no change
|
|
|
+ // LOG(WARNING) << m_range_status_last;
|
|
|
+
|
|
|
+ // 判断车辆旋转角超界情况
|
|
|
+ //huli new program 20221103, 使用 plc dispatch_1_statu_port 里面的 来做边界判断
|
|
|
+// double t_dtheta = 90-measure_result.car_angle; // 车身的旋转角, 修正到正负5度,
|
|
|
+ double t_dtheta = measure_result.car_angle + m_region.plc_offset_degree(); // 车身的旋转角, 修正到正5度, (m_region.plc_offset_degree():-89)
|
|
|
+ int t_terminal_id = m_region.region_id() +1; //region_id:0~5, terminal_id:1~6
|
|
|
+ //turnplate_angle_min = -5, turnplate_angle_max = 5,
|
|
|
+ if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max()+0.05)
|
|
|
+ {
|
|
|
+ m_range_status_last |= Range_status::Range_angle_anti_clock;
|
|
|
+ }
|
|
|
+ else if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max()-0.05)
|
|
|
+ {
|
|
|
+ int t = Range_status::Range_angle_anti_clock;
|
|
|
+ m_range_status_last &= (~t);
|
|
|
+ }
|
|
|
+ // LOG(WARNING) << m_range_status_last;
|
|
|
+
|
|
|
+ //else m_range_status_last no change
|
|
|
+ if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()-0.05)
|
|
|
+ {
|
|
|
+ res |= Range_status::Range_angle_clock;
|
|
|
+ }
|
|
|
+ else if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()+0.05)
|
|
|
+ {
|
|
|
+ int t = Range_status::Range_angle_clock;
|
|
|
+ m_range_status_last &= (~t);
|
|
|
+ }
|
|
|
+ // LOG(WARNING) << m_range_status_last;
|
|
|
+ // LOG(INFO) << t_dtheta<<", "<<System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()<<std::endl;
|
|
|
+ //else m_range_status_last no change
|
|
|
+
|
|
|
+ m_range_status_last |= outOfRangeDetection(cloud, plate_cx, plate_cy, theta);
|
|
|
+ return m_range_status_last;
|
|
|
+#endif
|
|
|
}
|
|
|
|
|
|
//外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
|