|
@@ -9,6 +9,11 @@ import (
|
|
|
"cicv-data-closedloop/common/util"
|
|
|
"cicv-data-closedloop/pjisuv_msgs"
|
|
|
"github.com/bluenviron/goroslib/v2"
|
|
|
+ "github.com/bluenviron/goroslib/v2/pkg/msgs/geometry_msgs"
|
|
|
+ "github.com/bluenviron/goroslib/v2/pkg/msgs/nav_msgs"
|
|
|
+ "github.com/bluenviron/goroslib/v2/pkg/msgs/sensor_msgs"
|
|
|
+ "github.com/bluenviron/goroslib/v2/pkg/msgs/tf2_msgs"
|
|
|
+ "github.com/bluenviron/goroslib/v2/pkg/msgs/visualization_msgs"
|
|
|
"sync"
|
|
|
"time"
|
|
|
)
|
|
@@ -32,19 +37,764 @@ func PrepareTimeWindowProducerQueue() {
|
|
|
subscribersMutexes := make([]sync.Mutex, len(commonConfig.SubscribeTopics))
|
|
|
for i, topic := range commonConfig.SubscribeTopics {
|
|
|
c_log.GlobalLogger.Info("创建订阅者订阅话题:" + topic)
|
|
|
+
|
|
|
+ // 1
|
|
|
+ if topic == masterConfig.TopicOfAmrPose && len(masterConfig.RuleOfAmrPose) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *visualization_msgs.MarkerArray) {
|
|
|
+ if len(masterConfig.TopicOfAmrPose) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfAmrPose {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 2
|
|
|
+ if topic == masterConfig.TopicOfBoundingBoxesFast && len(masterConfig.RuleOfBoundingBoxesFast) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.BoundingBoxArray) {
|
|
|
+ if len(masterConfig.TopicOfBoundingBoxesFast) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfBoundingBoxesFast {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 3
|
|
|
+ if topic == masterConfig.TopicOfCameraFault && len(masterConfig.RuleOfCameraFault) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.FaultVec) {
|
|
|
+ if len(masterConfig.TopicOfCameraFault) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCameraFault {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 4
|
|
|
+ if topic == masterConfig.TopicOfCanData && len(masterConfig.RuleOfCanData) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.Frame) {
|
|
|
+ if len(masterConfig.TopicOfCanData) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCanData {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 5
|
|
|
+ if topic == masterConfig.TopicOfCh128x1LslidarPointCloud && len(masterConfig.RuleOfCh128x1LslidarPointCloud) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.PointCloud2) {
|
|
|
+ if len(masterConfig.TopicOfCh128x1LslidarPointCloud) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCh128x1LslidarPointCloud {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 6
|
|
|
+ if topic == masterConfig.TopicOfCh64wLLslidarPointCloud && len(masterConfig.RuleOfCh64wLLslidarPointCloud) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.PointCloud2) {
|
|
|
+ if len(masterConfig.TopicOfCh64wLLslidarPointCloud) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCh64wLLslidarPointCloud {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 7
|
|
|
+ if topic == masterConfig.TopicOfCh64wLScan && len(masterConfig.RuleOfCh64wLScan) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.LaserScan) {
|
|
|
+ if len(masterConfig.TopicOfCh64wLScan) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCh64wLScan {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 8
|
|
|
+ if topic == masterConfig.TopicOfCh64wRLslidarPointCloud && len(masterConfig.RuleOfCh64wRLslidarPointCloud) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.PointCloud2) {
|
|
|
+ if len(masterConfig.TopicOfCh64wRLslidarPointCloud) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCh64wRLslidarPointCloud {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 9
|
|
|
+ if topic == masterConfig.TopicOfCh64wRScan && len(masterConfig.RuleOfCh64wRScan) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.LaserScan) {
|
|
|
+ if len(masterConfig.TopicOfCh64wRScan) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCh64wRScan {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 10
|
|
|
+ if topic == masterConfig.TopicOfCicvLidarclusterMovingObjects && len(masterConfig.RuleOfCicvLidarclusterMovingObjects) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.PerceptionCicvMovingObjects) {
|
|
|
+ if len(masterConfig.TopicOfCicvLidarclusterMovingObjects) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCicvLidarclusterMovingObjects {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 11
|
|
|
+ if topic == masterConfig.TopicOfCicvAmrTrajectory && len(masterConfig.RuleOfCicvAmrTrajectory) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.Trajectory) {
|
|
|
+ if len(masterConfig.TopicOfCicvAmrTrajectory) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCicvAmrTrajectory {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 12
|
|
|
if topic == masterConfig.TopicOfCicvLocation && len(masterConfig.RuleOfCicvLocation) > 0 {
|
|
|
subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
Node: commonConfig.RosNode,
|
|
|
Topic: topic,
|
|
|
- Callback: func(data *pjisuv_msgs.PerceptionLocalization) {
|
|
|
- // 更新共享变量
|
|
|
- m.RLock()
|
|
|
- velocityX = data.VelocityX
|
|
|
- velocityY = data.VelocityY
|
|
|
- yaw = data.Yaw
|
|
|
- m.RUnlock()
|
|
|
+ Callback: func(data *pjisuv_msgs.PerceptionLocalization) {
|
|
|
+ // 更新共享变量
|
|
|
+ m.RLock()
|
|
|
+ velocityX = data.VelocityX
|
|
|
+ velocityY = data.VelocityY
|
|
|
+ yaw = data.Yaw
|
|
|
+ m.RUnlock()
|
|
|
+
|
|
|
+ if len(masterConfig.TopicOfCicvLocation) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCicvLocation {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 13
|
|
|
+ if topic == masterConfig.TopicOfCloudClusters && len(masterConfig.RuleOfCloudClusters) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.AutowareCloudClusterArray) {
|
|
|
+ if len(masterConfig.TopicOfCloudClusters) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfCloudClusters {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 14
|
|
|
+ if topic == masterConfig.TopicOfHeartbeatInfo && len(masterConfig.RuleOfHeartbeatInfo) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.HeartBeatInfo) {
|
|
|
+ if len(masterConfig.TopicOfHeartbeatInfo) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfHeartbeatInfo {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 15
|
|
|
+ if topic == masterConfig.TopicOfLidarPretreatmentCost && len(masterConfig.RuleOfLidarPretreatmentCost) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *geometry_msgs.Vector3Stamped) {
|
|
|
+ if len(masterConfig.TopicOfLidarPretreatmentCost) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfLidarPretreatmentCost {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 16
|
|
|
+ if topic == masterConfig.TopicOfLidarPretreatmentOdometry && len(masterConfig.RuleOfLidarPretreatmentOdometry) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *nav_msgs.Odometry) {
|
|
|
+ if len(masterConfig.TopicOfLidarPretreatmentOdometry) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfLidarPretreatmentOdometry {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 17
|
|
|
+ if topic == masterConfig.TopicOfLidarRoi && len(masterConfig.RuleOfLidarRoi) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *geometry_msgs.PolygonStamped) {
|
|
|
+ if len(masterConfig.TopicOfLidarRoi) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfLidarRoi {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 18
|
|
|
+ if topic == masterConfig.TopicOfLine1 && len(masterConfig.RuleOfLine1) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *nav_msgs.Path) {
|
|
|
+ if len(masterConfig.TopicOfLine1) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfLine1 {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 19
|
|
|
+ if topic == masterConfig.TopicOfLine2 && len(masterConfig.RuleOfLine2) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *nav_msgs.Path) {
|
|
|
+ if len(masterConfig.TopicOfLine2) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfLine2 {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 20
|
|
|
+ if topic == masterConfig.TopicOfMapPolygon && len(masterConfig.RuleOfMapPolygon) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.PolygonStamped) {
|
|
|
+ if len(masterConfig.TopicOfMapPolygon) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfMapPolygon {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 21
|
|
|
+ if topic == masterConfig.TopicOfObstacleDisplay && len(masterConfig.RuleOfObstacleDisplay) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *visualization_msgs.MarkerArray) {
|
|
|
+ if len(masterConfig.TopicOfObstacleDisplay) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfObstacleDisplay {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 22
|
|
|
+ if topic == masterConfig.TopicOfPjControlPub && len(masterConfig.RuleOfPjControlPub) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.CommonVehicleCmd) {
|
|
|
+ if len(masterConfig.TopicOfPjControlPub) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfPjControlPub {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 23
|
|
|
+ if topic == masterConfig.TopicOfPointsCluster && len(masterConfig.RuleOfPointsCluster) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.PointCloud2) {
|
|
|
+ if len(masterConfig.TopicOfPointsCluster) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfPointsCluster {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 24
|
|
|
+ if topic == masterConfig.TopicOfPointsConcat && len(masterConfig.RuleOfPointsConcat) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.PointCloud2) {
|
|
|
+ if len(masterConfig.TopicOfPointsConcat) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfPointsConcat {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
|
|
|
- if len(masterConfig.TopicOfCicvLocation) == 0 {
|
|
|
+ // 25
|
|
|
+ if topic == masterConfig.TopicOfReferenceDisplay && len(masterConfig.RuleOfReferenceDisplay) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *nav_msgs.Path) {
|
|
|
+ if len(masterConfig.TopicOfReferenceDisplay) == 0 {
|
|
|
c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
return
|
|
|
}
|
|
@@ -54,10 +804,135 @@ func PrepareTimeWindowProducerQueue() {
|
|
|
faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
var faultLabel string
|
|
|
- for _, f := range masterConfig.RuleOfCicvLocation {
|
|
|
+ for _, f := range masterConfig.RuleOfReferenceDisplay {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 26
|
|
|
+ if topic == masterConfig.TopicOfReferenceTrajectory && len(masterConfig.RuleOfReferenceTrajectory) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.Trajectory) {
|
|
|
+ if len(masterConfig.TopicOfReferenceTrajectory) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfReferenceTrajectory {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 27
|
|
|
+ if topic == masterConfig.TopicOfRoiPoints && len(masterConfig.RuleOfRoiPoints) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.PointCloud2) {
|
|
|
+ if len(masterConfig.TopicOfRoiPoints) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfRoiPoints {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 28
|
|
|
+ if topic == masterConfig.TopicOfRoiPolygon && len(masterConfig.RuleOfRoiPolygon) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *nav_msgs.Path) {
|
|
|
+ if len(masterConfig.TopicOfRoiPolygon) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfRoiPolygon {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 29
|
|
|
+ if topic == masterConfig.TopicOfTf && len(masterConfig.RuleOfTf) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *tf2_msgs.TFMessage) {
|
|
|
+ if len(masterConfig.TopicOfTf) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfTf {
|
|
|
faultLabel = f(data)
|
|
|
if faultLabel != "" {
|
|
|
saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
break
|
|
|
}
|
|
|
}
|
|
@@ -68,6 +943,7 @@ func PrepareTimeWindowProducerQueue() {
|
|
|
})
|
|
|
}
|
|
|
|
|
|
+ // 30
|
|
|
if topic == masterConfig.TopicOfTpperception && len(masterConfig.RuleOfTpperception) > 0 {
|
|
|
subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
Node: commonConfig.RosNode,
|
|
@@ -97,6 +973,131 @@ func PrepareTimeWindowProducerQueue() {
|
|
|
})
|
|
|
}
|
|
|
|
|
|
+ // 31
|
|
|
+ if topic == masterConfig.TopicOfTpperceptionVis && len(masterConfig.RuleOfTpperceptionVis) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *visualization_msgs.MarkerArray) {
|
|
|
+ if len(masterConfig.TopicOfTpperceptionVis) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfTpperceptionVis {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 32
|
|
|
+ if topic == masterConfig.TopicOfTprouteplan && len(masterConfig.RuleOfTprouteplan) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *pjisuv_msgs.RoutePlan) {
|
|
|
+ if len(masterConfig.TopicOfTprouteplan) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfTprouteplan {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 33
|
|
|
+ if topic == masterConfig.TopicOfTrajectoryDisplay && len(masterConfig.RuleOfTrajectoryDisplay) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *nav_msgs.Path) {
|
|
|
+ if len(masterConfig.TopicOfTrajectoryDisplay) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfTrajectoryDisplay {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 34
|
|
|
+ if topic == masterConfig.TopicOfUngroundCloudpoints && len(masterConfig.RuleOfUngroundCloudpoints) > 0 {
|
|
|
+ subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
+ Node: commonConfig.RosNode,
|
|
|
+ Topic: topic,
|
|
|
+ Callback: func(data *sensor_msgs.PointCloud2) {
|
|
|
+ if len(masterConfig.TopicOfUngroundCloudpoints) == 0 {
|
|
|
+ c_log.GlobalLogger.Infof("话题 %v 没有触发器", topic)
|
|
|
+ return
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Lock()
|
|
|
+ if time.Since(subscribersTimes[i]).Seconds() > 1 {
|
|
|
+ subscribersMutexes[i].Lock()
|
|
|
+ faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
|
|
|
+ lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
|
|
|
+ var faultLabel string
|
|
|
+ for _, f := range masterConfig.RuleOfUngroundCloudpoints {
|
|
|
+ faultLabel = f(data)
|
|
|
+ if faultLabel != "" {
|
|
|
+ saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
|
|
|
+ subscribersTimes[i] = time.Now()
|
|
|
+ break
|
|
|
+ }
|
|
|
+ }
|
|
|
+ subscribersMutexes[i].Unlock()
|
|
|
+ }
|
|
|
+ subscribersTimeMutexes[i].Unlock()
|
|
|
+ },
|
|
|
+ })
|
|
|
+ }
|
|
|
+
|
|
|
+ // 35
|
|
|
if topic == masterConfig.TopicOfDataRead && len(masterConfig.RuleOfDataRead) > 0 {
|
|
|
subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
|
|
|
Node: commonConfig.RosNode,
|