Browse Source

0926 config update

yct 2 năm trước cách đây
mục cha
commit
0cddaf3c57
2 tập tin đã thay đổi với 78 bổ sung77 xóa
  1. 73 72
      setting/velodyne_manager.prototxt
  2. 5 5
      velodyne_lidar/ground_region.cpp

+ 73 - 72
setting/velodyne_manager.prototxt

@@ -6,31 +6,31 @@ distribution_mode:false
 
 #-----------------------------------lidars, id 0-6 from A1-C2
 
-# 6 lidar 192.168.1.201
-velodyne_lidars
-{
-    ip:""
-    port:2368
-    model:"VLP16"
-    calibrationFile:"../setting/VLP16db.yaml"
-    lidar_id:6
-    max_range:8.0
-    min_range:0.1
-    min_angle:0
-    max_angle:360
-    rpm:600
-    calib
-    {
-         r:-0.276397
-         p:-0.11717
-         y:89.6003
-         cz:0.05467
-        #r:-0.623165
-        #p:0.601821
-        #y:87.0198
-        #cz:0.101527
-    }
-}
+# # 6 lidar 192.168.1.201
+# velodyne_lidars
+# {
+#     ip:""
+#     port:2368
+#     model:"VLP16"
+#     calibrationFile:"../setting/VLP16db.yaml"
+#     lidar_id:6
+#     max_range:8.0
+#     min_range:0.1
+#     min_angle:0
+#     max_angle:360
+#     rpm:600
+#     calib
+#     {
+#          r:-0.276397
+#          p:-0.11717
+#          y:89.6003
+#          cz:0.05467
+#         #r:-0.623165
+#         #p:0.601821
+#         #y:87.0198
+#         #cz:0.101527
+#     }
+# }
 
 # 5 lidar 192.168.1.202
 velodyne_lidars
@@ -172,52 +172,52 @@ velodyne_lidars
 
 #-----------------------------------regions, 0-5 from A1 to C2
 
-# 5 region
-region
-{
-    minx:-1.6
-	maxx:1.6
-	miny:-2.6
-	maxy:2.6
-	minz:0.025
-	maxz:0.5
-    region_id:5
-    turnplate_cx:0.0
-    turnplate_cy:0.0
-    border_minx:-1.2
-    border_maxx:1.2
-    plc_offsetx:1.913
-    plc_offsety:-6.078
-    plc_offset_degree:-89.5
-    plc_border_miny:-7.51
-    car_min_width:1.55
-    car_max_width:1.92
-    car_min_wheelbase:2.3
-    car_max_wheelbase:3.15
-    turnplate_angle_limit_anti_clockwise:5.3
-    turnplate_angle_limit_clockwise:5.3
+# # 5 region
+# region
+# {
+#     minx:-1.6
+# 	maxx:1.6
+# 	miny:-2.6
+# 	maxy:2.6
+# 	minz:0.025
+# 	maxz:0.5
+#     region_id:5
+#     turnplate_cx:0.0
+#     turnplate_cy:0.0
+#     border_minx:-1.2
+#     border_maxx:1.2
+#     plc_offsetx:1.913
+#     plc_offsety:-6.078
+#     plc_offset_degree:-89.5
+#     plc_border_miny:-7.51
+#     car_min_width:1.55
+#     car_max_width:1.92
+#     car_min_wheelbase:2.3
+#     car_max_wheelbase:3.15
+#     turnplate_angle_limit_anti_clockwise:5.3
+#     turnplate_angle_limit_clockwise:5.3
 
-    lidar_exts
-    {
-        lidar_id:6
-        calib
-        {
-            cx:1.9018
-            cy:-0.0175
-        }
-    }
-    lidar_exts
-    {
-        lidar_id:5
-        calib
-        {
-            #cx:-4.021775
-            #cy:-0.039429
-            cx:-1.9018
-            cy:0.0175
-        }
-    }
-}
+#     lidar_exts
+#     {
+#         lidar_id:6
+#         calib
+#         {
+#             cx:1.9018
+#             cy:-0.0175
+#         }
+#     }
+#     lidar_exts
+#     {
+#         lidar_id:5
+#         calib
+#         {
+#             #cx:-4.021775
+#             #cy:-0.039429
+#             cx:-1.9018
+#             cy:0.0175
+#         }
+#     }
+# }
 
 # 4 region
 # 利用共用雷达标定plc偏移量
@@ -403,7 +403,7 @@ region
         lidar_id:2
         calib
         {
-            cx:1.89111#1.91111219
+            cx:1.89911#1.91111219
             cy:-0.053426
             cz:-0.005
             p:-1.5
@@ -415,8 +415,9 @@ region
         lidar_id:1
         calib
         {
-            cx:-1.89111#-1.91111219
+            cx:-1.89911#-1.91111219
             cy:0.053426
+            # p:0.5
         }
     }
 }

+ 5 - 5
velodyne_lidar/ground_region.cpp

@@ -569,9 +569,9 @@ Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, d
     // last_result.cy -= y;
     // last_result.theta -= theta;
 
-    // 角度校验,理论上car pose检测使用车身点云,应与车轮点云识别得到的车身 x偏移(0.025)与角度(<1°)一致
+    // 角度校验,理论上car pose检测使用车身点云,应与车轮点云识别得到的车身 x偏移(0.035)与角度(<1°)一致
     double car_pose_theta_deg = 90 - car_pose_theta * 180.0 / M_PI;
-    if (fabs(car_pose_x - last_result.cx) > 0.025 || fabs(car_pose_theta_deg - last_result.theta) > 1)
+    if (fabs(car_pose_x - last_result.cx) > 0.035 || fabs(car_pose_theta_deg - last_result.theta) > 1)
     {
         char valid_info[255];
         sprintf(valid_info, "validation failed for x and theta, carpose: (%.3f, %.3f), result: (%.3f, %.3f)", car_pose_x, car_pose_theta_deg, last_result.cx, last_result.theta);
@@ -864,12 +864,12 @@ void Ground_region::thread_measure_func()
                 // else{
                 //     std::cout<<ec.to_string()<<std::endl;
                 // }
-                 //LOG_IF(INFO, m_region.region_id() == 4) << m_car_wheel_information.to_string();
+                //  LOG_IF(INFO, m_region.region_id() == 1) << m_car_wheel_information.to_string();
             }
             else
             {
                 m_car_wheel_information.correctness = false;
-                // LOG_IF(ERROR, m_region.region_id() == 2) << ec.to_string();
+                // LOG_IF(ERROR, m_region.region_id() == 1) << ec.to_string();
 
                 // 20211228 added by yct, car movement checking, human and door detection
                 Error_manager car_status_res = Region_status_checker::get_instance_references().get_region_parking_status(m_region.region_id(), t_wheel_info_stamped_for_car_move, *mp_cloud_filtered);
@@ -880,7 +880,7 @@ void Ground_region::thread_measure_func()
                 }else
                 {
                     m_car_wheel_information.range_status |= Range_status::Range_car_moving;
-                    // if(m_region.region_id()==4){
+                    // if(m_region.region_id()==1){
                     //     std::cout<<"failed: "<<car_status_res.to_string()<<std::endl;
                     // }
                 }