Browse Source

20221207 border debug

yct 2 years ago
parent
commit
daa0a61d11

+ 1 - 0
.gitignore

@@ -36,3 +36,4 @@ packages/
 .idea*
 *.dll
 终端/ct_terminal/ct_terminal/Resource*
+build/

+ 2 - 2
入口引导提示节点/ui_config.json

@@ -1,8 +1,8 @@
 {
   "db": {"ip": "192.168.1.233","port": 3306,"database": "ct_project","user": "zx","password": "zx123456"},
   "rabbitmq": {"ip":"192.168.1.233","port":5672,"user":"zx","password":"zx123456"},
-  "led": {"ip": "192.168.1.160","port": 5005},
+  "led": {"ip": "192.168.1.163","port": 5005},
   "entrance_id": 1,
   "unit":1,
-  "prj": {"ip": "192.168.1.190","port": 4352,"type": 1}
+  "prj": {"ip": "192.168.1.193","port": 4352,"type": 1}
 }

+ 866 - 0
测量节点/back/wanji_manager.prototxt

@@ -0,0 +1,866 @@
+fence_data_path:"/home/zx/data/fence_wj"
+#fence_log_path:"/home/zx/yct/MainStructure/new_electronic_fence/log"
+distribution_mode:false
+
+#1
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.211"
+        port:2110
+    }
+    transform
+    {
+        m00:1
+	m01:0
+	m02:0#-1.6412
+	m10:0
+	m11:1
+	m12:0#-2.3441
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:0
+}
+
+#2
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.212"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.99992
+	m01:0.01236
+	m02:0#-1.6706
+	m10:-0.01236
+	m11:-0.99992
+	m12:0#2.3453
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:1
+}
+
+#3
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.213"
+        port:2110
+    }
+    transform
+    {
+        m00:0.99984
+	m01:-0.0177
+	m02:0#1.8655#-2.073
+	m10:0.0177
+	m11:0.99984
+	m12:0#-2.41#-2.263
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:2
+}
+
+#4
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.214"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.9976
+	m01:-0.06972
+	m02:0#1.8761#-1.9663
+	m10:0.06972
+	m11:-0.9976
+	m12:0#2.3286#2.3815
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:3
+}
+
+#5
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.215"
+        port:2110
+    }
+    transform
+    {
+        m00:0.99997
+	m01:0.00728
+	m02:0#1.8395#-1.9348
+	m10:-0.00728
+	m11:0.99997
+	m12:0#-2.4037#-2.2882
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:4
+}
+
+#6
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.216"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.9995
+	m01:-0.03147
+	m02:0#1.9198#-1.8524
+	m10:0.03417
+	m11:-0.9995
+	m12:0#2.24#2.3954
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:5
+}
+
+#7
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.217"
+        port:2110
+    }
+    transform
+    {
+        m00:1
+	m01:0
+	m02:0#1.9424#-1.8714
+	m10:0
+	m11:1
+	m12:0#-2.3569#-2.3391
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:6
+}
+
+#8
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.218"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.99554
+	m01:-0.0944
+	m02:0#1.9602#-1.8639
+	m10:0.0944
+	m11:-0.99554
+	m12:0#2.3309#2.3995
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:7
+}
+
+#9
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.219"
+        port:2110
+    }
+    transform
+    {
+        m00:1
+	m01:0
+	m02:0#-1.812
+	m10:0
+	m11:1
+	m12:0#-2.514
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:8
+}
+
+#10
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.220"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.9997
+	m01:0.02258
+	m02:0#-1.9153
+	m10:-0.02258
+	m11:-0.99974
+	m12:0#2.226
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:9
+}
+
+#11
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.221"
+        port:2110
+    }
+    transform
+    {
+        m00:0.99990
+	m01:-0.01445
+	m02:0#1.898#-1.839
+	m10:0.01445
+	m11:0.99990
+	m12:0#-2.356#-2.353
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-3.0
+        maxx:6.0
+        miny:-14
+        maxy:14
+    }
+    lidar_id:10
+}
+
+#12
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.222"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.99998
+	m01:0.00605
+	m02:0#1.8454#-1.9305
+	m10:-0.00605
+	m11:-0.99998
+	m12:0#2.3043#2.301
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:11
+}
+
+#13
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.223"
+        port:2110
+    }
+    transform
+    {
+        m00:0.99997
+	m01:-0.0078
+	m02:0#2.023
+	m10:0.0078
+	m11:0.99997
+	m12:0#-2.259
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:12
+}
+
+#14
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.224"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.99986
+	m01:0.01685
+	m02:0#1.916
+	m10:-0.01685
+	m11:-0.99986
+	m12:0#2.387
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:13
+}
+
+#1
+regions
+{
+	minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:0
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:0
+        calib
+        {
+            cx:-1.6412
+            cy:-2.3441
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:1
+        calib
+        {
+            cx:-1.6706
+            cy:2.3453
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:2
+        calib
+        {
+            cx:1.8655
+            cy:-2.41
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:3
+        calib
+        {
+            cx:1.8761
+            cy:2.3286
+        }
+    }
+}
+
+#2
+regions
+{
+	minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:1
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:2
+        calib
+        {
+            cx:-2.073
+            cy:-2.263
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:3
+        calib
+        {
+            cx:-1.9663
+            cy:2.3815
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:4
+        calib
+        {
+            cx:1.8395
+            cy:-2.4037
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:5
+        calib
+        {
+            cx:1.9198
+            cy:2.24
+        }
+    }
+}
+
+#3
+regions
+{
+	minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:2
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:4
+        calib
+        {
+            cx:-1.9348
+            cy:-2.2882
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:5
+        calib
+        {
+            cx:-1.8524
+            cy:2.3954
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:6
+        calib
+        {
+            cx:1.9424
+            cy:-2.3569
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:7
+        calib
+        {
+            cx:1.9602
+            cy:2.3309
+        }
+    }
+}
+
+#4
+regions
+{
+    # minx:8.7
+    # maxx:12
+    minx:-1.5
+    maxx:1.5
+    miny:-2.40
+    maxy:3.45
+
+    minz:0.025
+	maxz:0.5
+    region_id:3
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.3
+    border_maxx:1.3
+    plc_offsetx:0.0
+    plc_offsety:0.0
+    plc_offset_degree:0.0
+    plc_border_miny:-7.51
+    car_min_width:1.55
+    car_max_width:1.95
+    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.8714
+            cy:-2.3391
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:7
+        calib
+        {
+            cx:-1.8639
+            cy:2.3995
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:8
+        calib
+        {
+            cx:1.91
+            cy:-2.33
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:9
+        calib
+        {
+            cx:1.92
+            cy:2.33
+        }
+    }
+}
+
+#5
+regions
+{
+    minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:4
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:8
+        calib
+        {
+            cx:-1.812
+            cy:-2.514
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:9
+        calib
+        {
+            cx:-1.9153
+            cy:2.226
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:10
+        calib
+        {
+            cx:1.898
+            cy:-2.356
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:11
+        calib
+        {
+            cx:1.8454
+            cy:2.3043
+        }
+    }
+}
+
+#6
+regions
+{
+    minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:5
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:10
+        calib
+        {
+            cx:-1.839
+            cy:-2.353
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:11
+        calib
+        {
+            cx:-1.9305
+            cy:2.301
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:12
+        calib
+        {
+            cx:2.023
+            cy:-2.259
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:13
+        calib
+        {
+            cx:1.916
+            cy:2.387
+        }
+    }
+}
+

+ 866 - 0
测量节点/setting/wanji_manager_bak20221114.prototxt

@@ -0,0 +1,866 @@
+fence_data_path:"/home/zx/data/fence_wj"
+#fence_log_path:"/home/zx/yct/MainStructure/new_electronic_fence/log"
+distribution_mode:false
+
+#1
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.211"
+        port:2110
+    }
+    transform
+    {
+        m00:1
+	m01:0
+	m02:0#-1.6412
+	m10:0
+	m11:1
+	m12:0#-2.3441
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:0
+}
+
+#2
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.212"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.99992
+	m01:0.01236
+	m02:0#-1.6706
+	m10:-0.01236
+	m11:-0.99992
+	m12:0#2.3453
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:1
+}
+
+#3
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.213"
+        port:2110
+    }
+    transform
+    {
+        m00:0.99984
+	m01:-0.0177
+	m02:0#1.8655#-2.073
+	m10:0.0177
+	m11:0.99984
+	m12:0#-2.41#-2.263
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:2
+}
+
+#4
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.214"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.9976
+	m01:-0.06972
+	m02:0#1.8761#-1.9663
+	m10:0.06972
+	m11:-0.9976
+	m12:0#2.3286#2.3815
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:3
+}
+
+#5
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.215"
+        port:2110
+    }
+    transform
+    {
+        m00:0.99997
+	m01:0.00728
+	m02:0#1.8395#-1.9348
+	m10:-0.00728
+	m11:0.99997
+	m12:0#-2.4037#-2.2882
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:4
+}
+
+#6
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.216"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.9995
+	m01:-0.03147
+	m02:0#1.9198#-1.8524
+	m10:0.03417
+	m11:-0.9995
+	m12:0#2.24#2.3954
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:5
+}
+
+#7
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.217"
+        port:2110
+    }
+    transform
+    {
+        m00:1
+	m01:0
+	m02:0#1.9424#-1.8714
+	m10:0
+	m11:1
+	m12:0#-2.3569#-2.3391
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:6
+}
+
+#8
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.218"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.99554
+	m01:-0.0944
+	m02:0#1.9602#-1.8639
+	m10:0.0944
+	m11:-0.99554
+	m12:0#2.3309#2.3995
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:7
+}
+
+#9
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.219"
+        port:2110
+    }
+    transform
+    {
+        m00:1
+	m01:0
+	m02:0#-1.812
+	m10:0
+	m11:1
+	m12:0#-2.514
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:8
+}
+
+#10
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.220"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.9997
+	m01:0.02258
+	m02:0#-1.9153
+	m10:-0.02258
+	m11:-0.99974
+	m12:0#2.226
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:9
+}
+
+#11
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.221"
+        port:2110
+    }
+    transform
+    {
+        m00:0.99990
+	m01:-0.01445
+	m02:0#1.898#-1.839
+	m10:0.01445
+	m11:0.99990
+	m12:0#-2.356#-2.353
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-3.0
+        maxx:6.0
+        miny:-14
+        maxy:14
+    }
+    lidar_id:10
+}
+
+#12
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.222"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.99998
+	m01:0.00605
+	m02:0#1.8454#-1.9305
+	m10:-0.00605
+	m11:-0.99998
+	m12:0#2.3043#2.301
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:11
+}
+
+#13
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.223"
+        port:2110
+    }
+    transform
+    {
+        m00:0.99997
+	m01:-0.0078
+	m02:0#2.023
+	m10:0.0078
+	m11:0.99997
+	m12:0#-2.259
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:12
+}
+
+#14
+wj_lidar
+{
+    angle_min:-2.35619449
+    angle_max:2.35619449
+    angle_increment:0.00582
+    time_increment:0.000062
+    range_min:0
+    range_max:30
+    net_config
+    {
+        ip_address:"192.168.1.224"
+        port:2110
+    }
+    transform
+    {
+        m00:-0.99986
+	m01:0.01685
+	m02:0#1.916
+	m10:-0.01685
+	m11:-0.99986
+	m12:0#2.387
+    }
+    scan_limit
+    {
+        dist_limit:8
+        minx:-4.0
+        maxx:4.0
+        miny:-1.5
+        maxy:6.0
+    }
+    lidar_id:13
+}
+
+#1
+regions
+{
+	minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:0
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:0
+        calib
+        {
+            cx:-1.6412
+            cy:-2.3441
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:1
+        calib
+        {
+            cx:-1.6706
+            cy:2.3453
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:2
+        calib
+        {
+            cx:1.8655
+            cy:-2.41
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:3
+        calib
+        {
+            cx:1.8761
+            cy:2.3286
+        }
+    }
+}
+
+#2
+regions
+{
+	minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:1
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:2
+        calib
+        {
+            cx:-2.073
+            cy:-2.263
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:3
+        calib
+        {
+            cx:-1.9663
+            cy:2.3815
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:4
+        calib
+        {
+            cx:1.8395
+            cy:-2.4037
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:5
+        calib
+        {
+            cx:1.9198
+            cy:2.24
+        }
+    }
+}
+
+#3
+regions
+{
+	minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:2
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:4
+        calib
+        {
+            cx:-1.9348
+            cy:-2.2882
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:5
+        calib
+        {
+            cx:-1.8524
+            cy:2.3954
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:6
+        calib
+        {
+            cx:1.9424
+            cy:-2.3569
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:7
+        calib
+        {
+            cx:1.9602
+            cy:2.3309
+        }
+    }
+}
+
+#4
+regions
+{
+    # minx:8.7
+    # maxx:12
+    minx:-1.5
+    maxx:1.5
+    miny:-2.40
+    maxy:3.45
+
+    minz:0.025
+	maxz:0.5
+    region_id:3
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.3
+    border_maxx:1.3
+    plc_offsetx:0.0
+    plc_offsety:0.0
+    plc_offset_degree:0.0
+    plc_border_miny:-7.51
+    car_min_width:1.55
+    car_max_width:1.95
+    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.8714
+            cy:-2.3391
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:7
+        calib
+        {
+            cx:-1.8639
+            cy:2.3995
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:8
+        calib
+        {
+            cx:1.91
+            cy:-2.33
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:9
+        calib
+        {
+            cx:1.92
+            cy:2.33
+        }
+    }
+}
+
+#5
+regions
+{
+    minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:4
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:8
+        calib
+        {
+            cx:-1.812
+            cy:-2.514
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:9
+        calib
+        {
+            cx:-1.9153
+            cy:2.226
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:10
+        calib
+        {
+            cx:1.898
+            cy:-2.356
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:11
+        calib
+        {
+            cx:1.8454
+            cy:2.3043
+        }
+    }
+}
+
+#6
+regions
+{
+    minx:-1.42
+	maxx:1.5
+	miny:-2.6
+	maxy:2.3
+	minz:0.03
+	maxz:0.5
+    region_id:5
+    turnplate_cx:0.0
+    turnplate_cy:0.0
+    border_minx:-1.2
+    border_maxx:1.2
+    # -1.8683
+    plc_offsetx:-1.865
+    plc_offsety:-6.11489
+    plc_offset_degree:-89.6
+    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:10
+        calib
+        {
+            cx:-1.839
+            cy:-2.353
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:11
+        calib
+        {
+            cx:-1.9305
+            cy:2.301
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:12
+        calib
+        {
+            cx:2.023
+            cy:-2.259
+        }
+    }
+    lidar_exts
+    {
+        lidar_id:13
+        calib
+        {
+            cx:1.916
+            cy:2.387
+        }
+    }
+}
+

+ 11 - 3
测量节点/system/system_executor.cpp

@@ -655,14 +655,22 @@ Error_manager System_executor::encapsulate_send_mq_status()
 			else if(t_ground_status == message::Ground_statu::Car_border_reached)
 			{
 				t_multi_measure_info_msg.set_ground_status(3);
+			}else
+			{
+				t_multi_measure_info_msg.set_ground_status(2);
+				std::cout<<"system executor 661, original status "<<t_ground_status<<std::endl;
 			}
 			
+			// LOG(WARNING) << t_multi_status_msg.error_manager().error_description()<<std::endl;
 			std::string t_msg = t_multi_measure_info_msg.DebugString();
 			System_communication_mq::get_instance_references().encapsulate_status_msg(t_msg, t_multi_status_msg.id_struct().terminal_id());
 		}
 		if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
+		{
+			// LOG(WARNING) << t_car_wheel_information.range_status<<std::endl;
 			std::cout << t_multi_status_msg.DebugString() << std::endl
 						<< std::endl;
+		}
 	}
 }
 #endif
@@ -983,9 +991,9 @@ Error_manager System_executor::encapsulate_send_status()
 
 		std::string t_msg = t_multi_status_msg.SerializeAsString();
 		System_communication::get_instance_references().encapsulate_msg(t_msg);
-		if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
-			std::cout << t_multi_status_msg.DebugString() << std::endl
-						<< std::endl;
+		// if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
+		// 	std::cout << t_multi_status_msg.DebugString() << std::endl
+		// 				<< std::endl;
 	}
 }
 #endif

File diff suppressed because it is too large
+ 4461 - 0
测量节点/tests/region_4_26x.txt


File diff suppressed because it is too large
+ 11154 - 0
测量节点/tests/region_4_26x_g.txt


File diff suppressed because it is too large
+ 4576 - 0
测量节点/tests/region_4_env.txt


File diff suppressed because it is too large
+ 10905 - 0
测量节点/tests/region_4_env_g.txt


+ 113 - 20
测量节点/velodyne_lidar/ground_region.cpp

@@ -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
 }
 
 //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待

+ 8 - 0
测量节点/velodyne_lidar/ground_region.h

@@ -24,6 +24,10 @@
 #include <pcl/point_cloud.h>
 #include <pcl/filters/approximate_voxel_grid.h>
 
+
+//huli add fangdou
+#define ANTI_SHAKE  1
+
 class Ground_region
 {
 public:
@@ -185,6 +189,10 @@ private:
    Common_data::Car_wheel_information			m_car_wheel_information;		//车轮的定位结果,
 	std::chrono::system_clock::time_point		m_detect_update_time;			//定位结果的更新时间.
    std::mutex m_car_result_mutex; // 测量结果互斥锁
+
+#ifdef ANTI_SHAKE
+    int                m_range_status_last;
+#endif //ANTI_SHAKE
 };
 
 #endif //LIDARMEASURE__GROUD_REGION_HPP_