Explorar o código

modify All Trigger

zwh hai 9 meses
pai
achega
9512b2c75b
Modificáronse 22 ficheiros con 399 adicións e 54 borrados
  1. 62 1
      aarch64/pjisuv/master/service/produce_window.go
  2. 3 1
      trigger/pjisuv/cicv_location/AbnormalParking/main/AbnormalParking.go
  3. 3 1
      trigger/pjisuv/cicv_location/AuLongStop/main/AuLongStop.go
  4. 5 2
      trigger/pjisuv/cicv_location/Brake/main/Brake.go
  5. 82 0
      trigger/pjisuv/cicv_location/FindTrafficLightP1/main/FindTrafficLightP1.go
  6. 17 17
      trigger/pjisuv/cicv_location/FindTrafficLightP2/main/FindTrafficLightP2.go
  7. 82 0
      trigger/pjisuv/cicv_location/FindTrafficLightP3/main/FindTrafficLightP3.go
  8. 82 0
      trigger/pjisuv/cicv_location/FindTrafficLightP4/main/FindTrafficLightP4.go
  9. 4 2
      trigger/pjisuv/cicv_location/LocationJump/main/LocationJump.go
  10. 5 2
      trigger/pjisuv/cicv_location/OverSpeed/main/OverSpeed.go
  11. 4 2
      trigger/pjisuv/cicv_location/OverSwing/main/OverSwing.go
  12. 5 2
      trigger/pjisuv/cicv_location/RapidAccel/main/RapidAccel.go
  13. 6 5
      trigger/pjisuv/cicv_ticker/Example/main/Example.go
  14. 3 1
      trigger/pjisuv/map_polygon/OutOfLane/main/OutOfLane.go
  15. 4 2
      trigger/pjisuv/tpperception/NumTargetsExceedThreshold/main/NumTargetsExceedThreshold.go
  16. 4 2
      trigger/pjisuv/tpperception/TTC/main/TTC.go
  17. 5 2
      trigger/pjisuv/tpperception/TargetAhead/main/TargetAhead.go
  18. 4 2
      trigger/pjisuv/tpperception/TargetTooClose/main/TargetTooClose.go
  19. 4 2
      trigger/pjisuv/tpperception/TrafficCongestion/main/TrafficCongestion.go
  20. 5 3
      trigger/pjisuv/tpperception/UnknownBigTargetAhead/main/UnknownBigTargetAhead.go
  21. 5 3
      trigger/pjisuv/tpperception/lowSpdTruckAhead/main/lowSpdTruckAhead.go
  22. 5 2
      trigger/pjisuv/tpperception/multiTargetAhead/main/multiTargetAhead.go

+ 62 - 1
aarch64/pjisuv/master/service/produce_window.go

@@ -20,7 +20,18 @@ import (
 	"time"
 )
 
+type Point struct {
+	x, y float64
+}
+
 var (
+	//定义了车间四个边界点,将车间抽象成一个四边形
+	vertices = []Point{
+		{x: 456128.413, y: 4397847.78},
+		{x: 456288.257, y: 4397953.51},
+		{x: 456359.022, y: 4397822.84},
+		{x: 456191.065, y: 4397733.3},
+	}
 	cicvLocationTime = time.Now()
 	// -----------------------------共享变量
 	// /tpperception
@@ -597,7 +608,9 @@ func ProduceWindow() {
 						shareVars.Store("PositionYOfCicvLocation", data.PositionY)
 						// 用于判断是否在车间内
 						if time.Since(cicvLocationTime).Seconds() > 1 {
-							shareVars.Store("key", "value")
+							p := Point{x: data.PositionX, y: data.PositionY}
+							OutsideWorkshopFlag := isPointInPolygon(p, vertices) //在车间返回0,不在车间返回1
+							shareVars.Store("OutsideWorkshopFlag", OutsideWorkshopFlag)
 							cicvLocationTime = time.Now()
 						}
 					},
@@ -1893,3 +1906,51 @@ func getTopicsOfNode(faultLabel string) (masterTopics []string, slaveTopics []st
 	}
 	return masterTopics, slaveTopics
 }
+func isPointInPolygon(p Point, vertices []Point) bool {
+	intersections := 0
+	for i := 0; i < len(vertices); i++ {
+		j := (i + 1) % len(vertices)
+		if rayIntersectsSegment(p, vertices[i], vertices[j]) {
+			intersections++
+		}
+	}
+	return !(intersections%2 == 1)
+}
+
+func rayIntersectsSegment(p, p1, p2 Point) bool {
+	if p1.y > p2.y {
+		p1, p2 = p2, p1
+	}
+	if p.y == p1.y || p.y == p2.y {
+		p.y += 0.0001
+	}
+
+	if p.y < p1.y || p.y > p2.y {
+		return false
+	}
+
+	if p.x > max(p1.x, p2.x) {
+		return false
+	}
+
+	if p.x < min(p1.x, p2.x) {
+		return true
+	}
+
+	blueSlope := (p.y-p1.y)*(p2.x-p1.x)/(p2.y-p1.y) + p1.x
+	return p.x < blueSlope
+}
+
+func min(a, b float64) float64 {
+	if a < b {
+		return a
+	}
+	return b
+}
+
+func max(a, b float64) float64 {
+	if a > b {
+		return a
+	}
+	return b
+}

+ 3 - 1
trigger/pjisuv/cicv_location/AbnormalParking/main/AbnormalParking.go

@@ -74,6 +74,8 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
 		}
 	}()
 	if count1%10 == 0 {
+		OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+		OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
 		Automode, _ := shareVars.Load("AutomodeOfPjVehicleFdbPub")
 		Longitude, _ := shareVars.Load("EndPointX")
 		Latitude, _ := shareVars.Load("EndPointY")
@@ -83,7 +85,7 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
 		pointlist2 := []Point{EndPoint}
 		IsTrafficLight = IfEnter(pointlist1, 30.0, data.Latitude, data.Longitude)
 		IsEndPoint = IfEnter(pointlist2, 5.0, data.Latitude, data.Longitude)
-		if Automode == 1 && !IsTrafficLight && !IsEndPoint {
+		if Automode == 1 && !IsTrafficLight && !IsEndPoint && OutsideWorkshopFlag == true {
 			if data.VelocityX < 0.5 {
 				// 如果之前没有记录开始时间,记录当前时间
 				if StartTime == 0 {

+ 3 - 1
trigger/pjisuv/cicv_location/AuLongStop/main/AuLongStop.go

@@ -28,6 +28,8 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
 		}
 	}()
 	automodeOfPjVehicleFdbPub, ok := shareVars.Load("AutomodeOfPjVehicleFdbPub")
+	OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
 	if ok {
 		if automodeOfPjVehicleFdbPub.(int16) == 1 {
 			if data.VelocityX < 0.5 {
@@ -36,7 +38,7 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
 					StartTime = time.Now().Unix()
 				}
 				// 判断是否持续超过 50s
-				if time.Now().Unix()-StartTime > 50 {
+				if time.Now().Unix()-StartTime > 50 && OutsideWorkshopFlag == true {
 					if !IsStopped {
 						IsStopped = true
 						return Label()

+ 5 - 2
trigger/pjisuv/cicv_location/Brake/main/Brake.go

@@ -3,6 +3,7 @@ package main
 import (
 	"cicv-data-closedloop/pjisuv_msgs"
 	"fmt"
+	"sync"
 )
 
 func Topic() string {
@@ -14,13 +15,15 @@ func Label() string {
 	return "Brake"
 }
 
-func Rule(data *pjisuv_msgs.PerceptionLocalization) string {
+func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string {
 	defer func() {
 		if r := recover(); r != nil {
 			fmt.Println("Recovered from panic:", r)
 		}
 	}()
-	if data.AccelX*9.8 < -14.0 {
+	OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
+	if data.AccelX*9.8 < -14.0 && OutsideWorkshopFlag == true {
 		return Label()
 	}
 	return ""

+ 82 - 0
trigger/pjisuv/cicv_location/FindTrafficLightP1/main/FindTrafficLightP1.go

@@ -0,0 +1,82 @@
+package main
+
+import (
+	"cicv-data-closedloop/pjisuv_msgs"
+	"fmt"
+	"math"
+	"sync"
+)
+
+func Topic() string {
+	return "/cicv_location"
+}
+
+// todo 禁止存在下划线_
+func Label() string {
+	return "FindTrafficLight"
+}
+
+type Point struct {
+	Latitude  float64
+	Longitude float64
+}
+
+var (
+	count1 int = 0
+
+	//定义园区4个信号灯的坐标
+	point = Point{39.72975930689718, 116.48861102824081}
+	//point3 = Point{39.7288805296616, 116.48812315228867}
+	//point4 = Point{39.73061430369551, 116.49225103553502}
+	//point5 = Point{39.73077491578002, 116.49060085035634}
+
+	//pointlist = []Point{point2, point3, point4, point5}
+)
+
+func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string {
+	defer func() {
+		if r := recover(); r != nil {
+			fmt.Println("Recovered from panic:", r)
+		}
+	}()
+	if count1%10 == 0 {
+
+		enterflag := IfEnter(point, 25.0, data.Latitude, data.Longitude)
+		VelocityXOfCicvLocation, _ := shareVars.Load("VelocityXOfCicvLocation")
+		if enterflag && VelocityXOfCicvLocation.(float64) > 1 {
+			//eventLabel := "FindTrafficLight"
+			//fmt.Println(eventLabel)
+			return "FindTrafficLightP1"
+		}
+	}
+	count1++
+	return ""
+}
+
+func IfEnter(point Point, radius float64, lat, lon float64) bool {
+	// 判断是否进入点列表中的区域
+	point1 := Point{Latitude: lat, Longitude: lon}
+	d := distance(point1, point)
+	if d <= radius {
+		return true
+	}
+
+	return false
+}
+
+// 计算两点之间的距离(米)
+func distance(point1, point2 Point) float64 {
+	// 经纬度转弧度
+	lat1 := point1.Latitude * math.Pi / 180
+	lon1 := point1.Longitude * math.Pi / 180
+	lat2 := point2.Latitude * math.Pi / 180
+	lon2 := point2.Longitude * math.Pi / 180
+
+	// 计算距离
+	dlon := lon2 - lon1
+	dlat := lat2 - lat1
+	a := math.Sin(dlat/2)*math.Sin(dlat/2) + math.Sin(dlon/2)*math.Sin(dlon/2)*math.Cos(lat1)*math.Cos(lat2)
+	c := 2 * math.Atan2(math.Sqrt(a), math.Sqrt(1-a))
+	d := 6371000 * c
+	return d
+}

+ 17 - 17
trigger/pjisuv/cicv_location/FindTrafficLight/main/FindTrafficLight.go → trigger/pjisuv/cicv_location/FindTrafficLightP2/main/FindTrafficLightP2.go

@@ -25,12 +25,12 @@ var (
 	count1 int = 0
 
 	//定义园区4个信号灯的坐标
-	point2 = Point{39.72975930689718, 116.48861102824081}
-	point3 = Point{39.7288805296616, 116.48812315228867}
-	point4 = Point{39.73061430369551, 116.49225103553502}
-	point5 = Point{39.73077491578002, 116.49060085035634}
+	//point = Point{39.72975930689718, 116.48861102824081}
+	point = Point{39.7288805296616, 116.48812315228867}
+	//point4 = Point{39.73061430369551, 116.49225103553502}
+	//point5 = Point{39.73077491578002, 116.49060085035634}
 
-	pointlist = []Point{point2, point3, point4, point5}
+	//pointlist = []Point{point2, point3, point4, point5}
 )
 
 func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string {
@@ -40,27 +40,27 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
 		}
 	}()
 	if count1%10 == 0 {
-		enterflag := IfEnter(pointlist, 25.0, data.Latitude, data.Longitude)
-		velocityXOfCicvLocation, ok := shareVars.Load("VelocityXOfCicvLocation")
-		if ok {
-			if enterflag && velocityXOfCicvLocation.(float64) >= 1 {
-				return Label()
-			}
+
+		enterflag := IfEnter(point, 25.0, data.Latitude, data.Longitude)
+		VelocityXOfCicvLocation, _ := shareVars.Load("VelocityXOfCicvLocation")
+		if enterflag && VelocityXOfCicvLocation.(float64) > 1 {
+			//eventLabel := "FindTrafficLight"
+			//fmt.Println(eventLabel)
+			return "FindTrafficLightP1"
 		}
 	}
 	count1++
 	return ""
 }
 
-func IfEnter(pointlist []Point, radius float64, lat, lon float64) bool {
+func IfEnter(point Point, radius float64, lat, lon float64) bool {
 	// 判断是否进入点列表中的区域
 	point1 := Point{Latitude: lat, Longitude: lon}
-	for _, point := range pointlist {
-		d := distance(point1, point)
-		if d <= radius {
-			return true
-		}
+	d := distance(point1, point)
+	if d <= radius {
+		return true
 	}
+
 	return false
 }
 

+ 82 - 0
trigger/pjisuv/cicv_location/FindTrafficLightP3/main/FindTrafficLightP3.go

@@ -0,0 +1,82 @@
+package main
+
+import (
+	"cicv-data-closedloop/pjisuv_msgs"
+	"fmt"
+	"math"
+	"sync"
+)
+
+func Topic() string {
+	return "/cicv_location"
+}
+
+// todo 禁止存在下划线_
+func Label() string {
+	return "FindTrafficLight"
+}
+
+type Point struct {
+	Latitude  float64
+	Longitude float64
+}
+
+var (
+	count1 int = 0
+
+	//定义园区4个信号灯的坐标
+	//point = Point{39.72975930689718, 116.48861102824081}
+	//point3 = Point{39.7288805296616, 116.48812315228867}
+	point = Point{39.73061430369551, 116.49225103553502}
+	//point5 = Point{39.73077491578002, 116.49060085035634}
+
+	//pointlist = []Point{point2, point3, point4, point5}
+)
+
+func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string {
+	defer func() {
+		if r := recover(); r != nil {
+			fmt.Println("Recovered from panic:", r)
+		}
+	}()
+	if count1%10 == 0 {
+
+		enterflag := IfEnter(point, 25.0, data.Latitude, data.Longitude)
+		VelocityXOfCicvLocation, _ := shareVars.Load("VelocityXOfCicvLocation")
+		if enterflag && VelocityXOfCicvLocation.(float64) > 1 {
+			//eventLabel := "FindTrafficLight"
+			//fmt.Println(eventLabel)
+			return "FindTrafficLightP1"
+		}
+	}
+	count1++
+	return ""
+}
+
+func IfEnter(point Point, radius float64, lat, lon float64) bool {
+	// 判断是否进入点列表中的区域
+	point1 := Point{Latitude: lat, Longitude: lon}
+	d := distance(point1, point)
+	if d <= radius {
+		return true
+	}
+
+	return false
+}
+
+// 计算两点之间的距离(米)
+func distance(point1, point2 Point) float64 {
+	// 经纬度转弧度
+	lat1 := point1.Latitude * math.Pi / 180
+	lon1 := point1.Longitude * math.Pi / 180
+	lat2 := point2.Latitude * math.Pi / 180
+	lon2 := point2.Longitude * math.Pi / 180
+
+	// 计算距离
+	dlon := lon2 - lon1
+	dlat := lat2 - lat1
+	a := math.Sin(dlat/2)*math.Sin(dlat/2) + math.Sin(dlon/2)*math.Sin(dlon/2)*math.Cos(lat1)*math.Cos(lat2)
+	c := 2 * math.Atan2(math.Sqrt(a), math.Sqrt(1-a))
+	d := 6371000 * c
+	return d
+}

+ 82 - 0
trigger/pjisuv/cicv_location/FindTrafficLightP4/main/FindTrafficLightP4.go

@@ -0,0 +1,82 @@
+package main
+
+import (
+	"cicv-data-closedloop/pjisuv_msgs"
+	"fmt"
+	"math"
+	"sync"
+)
+
+func Topic() string {
+	return "/cicv_location"
+}
+
+// todo 禁止存在下划线_
+func Label() string {
+	return "FindTrafficLight"
+}
+
+type Point struct {
+	Latitude  float64
+	Longitude float64
+}
+
+var (
+	count1 int = 0
+
+	//定义园区4个信号灯的坐标
+	//point = Point{39.72975930689718, 116.48861102824081}
+	//point3 = Point{39.7288805296616, 116.48812315228867}
+	//point4 = Point{39.73061430369551, 116.49225103553502}
+	point = Point{39.73077491578002, 116.49060085035634}
+
+	//pointlist = []Point{point2, point3, point4, point5}
+)
+
+func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string {
+	defer func() {
+		if r := recover(); r != nil {
+			fmt.Println("Recovered from panic:", r)
+		}
+	}()
+	if count1%10 == 0 {
+
+		enterflag := IfEnter(point, 25.0, data.Latitude, data.Longitude)
+		VelocityXOfCicvLocation, _ := shareVars.Load("VelocityXOfCicvLocation")
+		if enterflag && VelocityXOfCicvLocation.(float64) > 1 {
+			//eventLabel := "FindTrafficLight"
+			//fmt.Println(eventLabel)
+			return "FindTrafficLightP1"
+		}
+	}
+	count1++
+	return ""
+}
+
+func IfEnter(point Point, radius float64, lat, lon float64) bool {
+	// 判断是否进入点列表中的区域
+	point1 := Point{Latitude: lat, Longitude: lon}
+	d := distance(point1, point)
+	if d <= radius {
+		return true
+	}
+
+	return false
+}
+
+// 计算两点之间的距离(米)
+func distance(point1, point2 Point) float64 {
+	// 经纬度转弧度
+	lat1 := point1.Latitude * math.Pi / 180
+	lon1 := point1.Longitude * math.Pi / 180
+	lat2 := point2.Latitude * math.Pi / 180
+	lon2 := point2.Longitude * math.Pi / 180
+
+	// 计算距离
+	dlon := lon2 - lon1
+	dlat := lat2 - lat1
+	a := math.Sin(dlat/2)*math.Sin(dlat/2) + math.Sin(dlon/2)*math.Sin(dlon/2)*math.Cos(lat1)*math.Cos(lat2)
+	c := 2 * math.Atan2(math.Sqrt(a), math.Sqrt(1-a))
+	d := 6371000 * c
+	return d
+}

+ 4 - 2
trigger/pjisuv/cicv_location/LocationJump/main/LocationJump.go

@@ -23,14 +23,16 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
 			fmt.Println("Recovered from panic:", r)
 		}
 	}()
+	OutsideWorkshopFlag, ok3 := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
 	positionXOfCicvLocation, ok1 := shareVars.Load("PositionXOfCicvLocation")
 	positionYOfCicvLocation, ok2 := shareVars.Load("PositionYOfCicvLocation")
-	if ok1 && ok2 {
+	if ok1 && ok2 && ok3 {
 		v1 := positionXOfCicvLocation.(float64)
 		v2 := positionYOfCicvLocation.(float64)
 		if v1 != 0 && v2 != 0 {
 			d := math.Sqrt((v1-data.PositionX)*(v1-data.PositionX) + (v2-data.PositionY)*(v2-data.PositionY))
-			if d >= 2 {
+			if d >= 2 && OutsideWorkshopFlag == true {
 				return Label()
 			}
 		}

+ 5 - 2
trigger/pjisuv/cicv_location/OverSpeed/main/OverSpeed.go

@@ -4,6 +4,7 @@ import (
 	"cicv-data-closedloop/pjisuv_msgs"
 	"fmt"
 	"math"
+	"sync"
 )
 
 func Topic() string {
@@ -14,15 +15,17 @@ func Label() string {
 	return "OverSpeed"
 }
 
-func Rule(data *pjisuv_msgs.PerceptionLocalization) string {
+func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string {
 	defer func() {
 		if r := recover(); r != nil {
 			fmt.Println("Recovered from panic:", r)
 		}
 	}()
 	//threshold := 65.0
+	OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
 	threshold := 9999.0
-	if math.Pow(math.Pow(data.VelocityX, 2)+math.Pow(data.VelocityY, 2), 0.5)*3.6 >= threshold {
+	if math.Pow(math.Pow(data.VelocityX, 2)+math.Pow(data.VelocityY, 2), 0.5)*3.6 >= threshold && OutsideWorkshopFlag == true {
 		return "OverSpeed"
 	} else {
 		return ""

+ 4 - 2
trigger/pjisuv/cicv_location/OverSwing/main/OverSwing.go

@@ -42,8 +42,10 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string
 		}
 	}()
 	automodeOfPjVehicleFdbPub, ok := shareVars.Load("AutomodeOfPjVehicleFdbPub")
-	if ok {
-		if math.Abs(data.AngularVelocityZ) >= 27.0 && automodeOfPjVehicleFdbPub.(int16) == 1 {
+	OutsideWorkshopFlag, ok1 := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
+	if ok && ok1 {
+		if math.Abs(data.AngularVelocityZ) >= 27.0 && automodeOfPjVehicleFdbPub.(int16) == 1 && OutsideWorkshopFlag == true {
 			return Label()
 		}
 	}

+ 5 - 2
trigger/pjisuv/cicv_location/RapidAccel/main/RapidAccel.go

@@ -3,6 +3,7 @@ package main
 import (
 	"cicv-data-closedloop/pjisuv_msgs"
 	"fmt"
+	"sync"
 )
 
 func Topic() string {
@@ -13,13 +14,15 @@ func Label() string {
 	return "RapidAccel"
 }
 
-func Rule(data *pjisuv_msgs.PerceptionLocalization) string {
+func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionLocalization) string {
 	defer func() {
 		if r := recover(); r != nil {
 			fmt.Println("Recovered from panic:", r)
 		}
 	}()
-	if data.AccelX*9.8 > 5.0 {
+	OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
+	if data.AccelX*9.8 > 5.0 && OutsideWorkshopFlag == true {
 		return Label()
 	} else {
 		return ""

+ 6 - 5
trigger/pjisuv/cicv_ticker/Example/main/Example.go

@@ -15,7 +15,7 @@ func Topic() string {
 // ******* 禁止存在下划线_
 // 触发器标记
 func Label() string {
-	return "Example"
+	return "FrontVehicleCutInFar"
 }
 
 func Rule(shareVars *sync.Map) {
@@ -34,11 +34,12 @@ func Rule(shareVars *sync.Map) {
 			select {
 			// 定时器触发时执行的代码
 			case <-ticker.C:
-				if true {
-					// 将错误Label发送到channel通道中
-					pjisuv_ticker.TickerChan <- pjisuv_ticker.TickInfo{FaultLabel: Label(), FaultHappenTime: pjisuv_ticker.GetNowTimeCustom()}
-				}
+				FinalCallback(shareVars)
+
 			}
 		}
 	}(shareVars)
 }
+func FinalCallback(shareVars *sync.Map) {
+	pjisuv_ticker.TickerChan <- pjisuv_ticker.TickInfo{FaultLabel: Label(), FaultHappenTime: pjisuv_ticker.GetNowTimeCustom()}
+}

+ 3 - 1
trigger/pjisuv/map_polygon/OutOfLane/main/OutOfLane.go

@@ -27,6 +27,8 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PolygonStamped) string {
 	positionYOfCicvLocation, ok2 := shareVars.Load("PositionYOfCicvLocation")
 	yawOfCicvLocation, ok3 := shareVars.Load("YawOfCicvLocation")
 	automodeOfPjVehicleFdbPub, ok4 := shareVars.Load("AutomodeOfPjVehicleFdbPub")
+	OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
 	if ok1 && ok2 && ok3 && ok4 {
 		Points := data.Polygon.Points
 		D1, D2, D3 := 1.0, 0.4, 0.4 //这是实车缩小后的尺寸
@@ -34,7 +36,7 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PolygonStamped) string {
 		for i := 0; i < len(Points)-1; i++ {
 			A := Points[i]
 			B := Points[i+1]
-			if polygonLineIntersect(corners, A, B) && automodeOfPjVehicleFdbPub.(int16) == 1 {
+			if polygonLineIntersect(corners, A, B) && automodeOfPjVehicleFdbPub.(int16) == 1 && OutsideWorkshopFlag == true {
 				return Label()
 			}
 		}

+ 4 - 2
trigger/pjisuv/tpperception/NumTargetsExceedThreshold/main/NumTargetsExceedThreshold.go

@@ -22,8 +22,10 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionObjects) string {
 		}
 	}()
 	velocityXOfCicvLocation, ok := shareVars.Load("VelocityXOfCicvLocation")
-	if ok {
-		if velocityXOfCicvLocation.(float64) > 2.5 && len(data.Objs) > 6 {
+	OutsideWorkshopFlag, ok1 := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
+	if ok && ok1 {
+		if velocityXOfCicvLocation.(float64) > 2.5 && len(data.Objs) > 6 && OutsideWorkshopFlag == true {
 			for _, obj := range data.Objs {
 				if obj.Type != 0 && obj.X >= 2 {
 					NumTargets++

+ 4 - 2
trigger/pjisuv/tpperception/TTC/main/TTC.go

@@ -44,12 +44,14 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionObjects) string {
 	}()
 
 	velocityXOfCicvLocation, ok := shareVars.Load("VelocityXOfCicvLocation")
-	if ok {
+	OutsideWorkshopFlag, ok1 := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
+	if ok && ok1 {
 		value := velocityXOfCicvLocation.(float64)
 		for _, obj := range data.Objs {
 			if math.Abs(float64(obj.Y)) <= 2 && obj.X >= 6 && value > 0.5 {
 				ttc := -((float64(obj.X) - 4) / (float64(obj.Vxrel) + 0.001))
-				if ttc >= 0 && ttc <= 3 {
+				if ttc >= 0 && ttc <= 3 && OutsideWorkshopFlag == true {
 					return Label()
 				}
 			}

+ 5 - 2
trigger/pjisuv/tpperception/TargetAhead/main/TargetAhead.go

@@ -24,11 +24,14 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionObjects) string {
 	}()
 	velocityXOfCicvLocation, ok1 := shareVars.Load("VelocityXOfCicvLocation")
 	angularVelocityZOfCicvLocation, ok2 := shareVars.Load("AngularVelocityZOfCicvLocation")
-	if ok1 && ok2 {
+	OutsideWorkshopFlag, ok3 := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
+
+	if ok1 && ok2 && ok3 {
 		value1 := velocityXOfCicvLocation.(float64)
 		value2 := angularVelocityZOfCicvLocation.(float64)
 		for _, obj := range data.Objs {
-			if math.Abs(float64(obj.Y)) <= 2.3 && obj.X >= 0 && obj.X <= 13 && value1 < 5.5 && math.Abs(value2) >= 0.5 {
+			if math.Abs(float64(obj.Y)) <= 2.3 && obj.X >= 0 && obj.X <= 13 && value1 < 5.5 && math.Abs(value2) >= 0.5 && OutsideWorkshopFlag == true {
 				return Label()
 			}
 		}

+ 4 - 2
trigger/pjisuv/tpperception/TargetTooClose/main/TargetTooClose.go

@@ -23,11 +23,13 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionObjects) string {
 	}()
 	velocityXOfCicvLocation, ok1 := shareVars.Load("VelocityXOfCicvLocation")
 	angularVelocityZOfCicvLocation, ok2 := shareVars.Load("AngularVelocityZOfCicvLocation")
-	if ok1 && ok2 {
+	OutsideWorkshopFlag, ok3 := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
+	if ok1 && ok2 && ok3 {
 		for _, obj := range data.Objs {
 			value1 := velocityXOfCicvLocation.(float64)
 			value2 := angularVelocityZOfCicvLocation.(float64)
-			if math.Abs(float64(obj.Y)) <= 1.5 && obj.X >= 0 && obj.X <= 6 && value1 < 5.5 && math.Abs(value2) >= 0.5 {
+			if math.Abs(float64(obj.Y)) <= 1.5 && obj.X >= 0 && obj.X <= 6 && value1 < 5.5 && math.Abs(value2) >= 0.5 && OutsideWorkshopFlag == true {
 				return Label()
 			}
 		}

+ 4 - 2
trigger/pjisuv/tpperception/TrafficCongestion/main/TrafficCongestion.go

@@ -23,14 +23,16 @@ func Rule(shareVars *sync.Map, data *pjisuv_msgs.PerceptionObjects) string {
 		}
 	}()
 	velocityXOfCicvLocation, ok := shareVars.Load("VelocityXOfCicvLocation")
-	if ok {
+	OutsideWorkshopFlag, ok1 := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
+	if ok && ok1 {
 		if velocityXOfCicvLocation.(float64) < 3.5 && len(data.Objs) > 3 {
 			for _, obj := range data.Objs {
 				if (obj.Type == 2 || obj.Type == 3) && math.Abs(float64(obj.Y)) <= 2.5 && math.Abs(float64(obj.X)) <= 20 && obj.Speed <= 4 {
 					NumTargets++
 				}
 			}
-			if NumTargets >= 3 {
+			if NumTargets >= 3 && OutsideWorkshopFlag == true {
 				return Label()
 
 			}

+ 5 - 3
trigger/pjisuv/tpperception/UnknownBigTargetAhead/main/UnknownBigTargetAhead.go

@@ -4,6 +4,7 @@ import (
 	"cicv-data-closedloop/pjisuv_msgs"
 	"fmt"
 	"math"
+	"sync"
 )
 
 func Topic() string {
@@ -67,7 +68,7 @@ func posCheck(obj *pjisuv_msgs.PerceptionObject) bool {
 }
 
 // Rule 检测前方未知大目标物
-func Rule(msg *pjisuv_msgs.PerceptionObjects) string {
+func Rule(shareVars *sync.Map, msg *pjisuv_msgs.PerceptionObjects) string {
 	defer func() {
 		if r := recover(); r != nil {
 			fmt.Println(fmt.Sprintf("Recovered from panic: [%s], [%#v]", Label(), r))
@@ -76,7 +77,8 @@ func Rule(msg *pjisuv_msgs.PerceptionObjects) string {
 
 	const MinStableFrameCount = 5   // frame
 	const MaxTimeBetweenFrame = 0.5 // second
-
+	OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
 	for _, obj := range msg.Objs {
 
 		// 判断目标物是否满足筛选条件
@@ -99,7 +101,7 @@ func Rule(msg *pjisuv_msgs.PerceptionObjects) string {
 				// 目标物确认/更新/重置
 				if currObjRecord.LastExistingTime-prevObjRecord.LastExistingTime <= MaxTimeBetweenFrame { // 目标物消失不超过0.5s
 					currObjRecord.StableFrame = prevObjRecord.StableFrame + 1
-					if currObjRecord.StableFrame == MinStableFrameCount {
+					if currObjRecord.StableFrame == MinStableFrameCount && OutsideWorkshopFlag == true {
 						delete(objectsStability, obj.Id)
 						return Label()
 					}

+ 5 - 3
trigger/pjisuv/tpperception/lowSpdTruckAhead/main/lowSpdTruckAhead.go

@@ -4,6 +4,7 @@ import (
 	"cicv-data-closedloop/pjisuv_msgs"
 	"fmt"
 	"math"
+	"sync"
 )
 
 type Object struct {
@@ -48,13 +49,14 @@ func posCheck(obj *pjisuv_msgs.PerceptionObject) bool {
 }
 
 // Rule 检测前方大车低速行驶
-func Rule(msg *pjisuv_msgs.PerceptionObjects) string {
+func Rule(shareVars *sync.Map, msg *pjisuv_msgs.PerceptionObjects) string {
 	defer func() {
 		if r := recover(); r != nil {
 			fmt.Println(fmt.Sprintf("Recovered from panic: [%s], [%#v]", Label(), r))
 		}
 	}()
-
+	OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
 	const MinStableFrameCount = 5
 	const MaxTimeBetweenFrame = 0.5
 
@@ -80,7 +82,7 @@ func Rule(msg *pjisuv_msgs.PerceptionObjects) string {
 				// 目标物确认/更新/重置
 				if currObjRecord.LastExistTime-prevObjRecord.LastExistTime <= MaxTimeBetweenFrame { // 目标物消失不超过0.5s
 					currObjRecord.StableAge = prevObjRecord.StableAge + 1
-					if currObjRecord.StableAge == MinStableFrameCount {
+					if currObjRecord.StableAge == MinStableFrameCount && OutsideWorkshopFlag == true {
 						delete(objectsStability, obj.Id)
 						return Label()
 					}

+ 5 - 2
trigger/pjisuv/tpperception/multiTargetAhead/main/multiTargetAhead.go

@@ -4,6 +4,7 @@ import (
 	"cicv-data-closedloop/pjisuv_msgs"
 	"fmt"
 	"math"
+	"sync"
 )
 
 func Topic() string {
@@ -45,7 +46,7 @@ func posCheck(obj *pjisuv_msgs.PerceptionObject) bool {
 }
 
 // Rule 检测前方指定目标物数量
-func Rule(msg *pjisuv_msgs.PerceptionObjects) string {
+func Rule(shareVars *sync.Map, msg *pjisuv_msgs.PerceptionObjects) string {
 	defer func() {
 		if r := recover(); r != nil {
 			fmt.Println("Recovered from panic:", r)
@@ -57,6 +58,8 @@ func Rule(msg *pjisuv_msgs.PerceptionObjects) string {
 	const MinStableFrameCount = 5   // frame
 	const MaxTimeBetweenFrame = 0.5 // second
 	const minTargetNum = 4
+	OutsideWorkshopFlag, _ := shareVars.Load("OutsideWorkshopFlag")
+	OutsideWorkshopFlag = OutsideWorkshopFlag.(bool)
 
 	if len(msg.Objs) >= minTargetNum {
 
@@ -83,7 +86,7 @@ func Rule(msg *pjisuv_msgs.PerceptionObjects) string {
 
 				if newRecord.LastExistingTime-record.LastExistingTime <= MaxTimeBetweenFrame {
 					newRecord.StableFrame = record.StableFrame + 1
-					if newRecord.StableFrame == MinStableFrameCount {
+					if newRecord.StableFrame == MinStableFrameCount && OutsideWorkshopFlag == true {
 						record = nil
 						return Label()
 					} else {