12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262 |
- package service
- import (
- commonConfig "cicv-data-closedloop/aarch64/pjisuv/common/config"
- "cicv-data-closedloop/aarch64/pjisuv/common/service"
- masterConfig "cicv-data-closedloop/aarch64/pjisuv/master/config"
- "cicv-data-closedloop/common/config/c_log"
- commonEntity "cicv-data-closedloop/common/entity"
- "cicv-data-closedloop/common/util"
- "cicv-data-closedloop/pjisuv_msgs"
- "cicv-data-closedloop/pjisuv_param"
- "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"
- "math"
- "sync"
- "time"
- )
- // 所有共享变量
- var (
- pjisuvParam = pjisuv_param.PjisuvParam{
- ObjDicOfTpperception: make(map[uint32][]float32),
- ObjTypeDicOfTpperception: make(map[uint32]uint8),
- ObjSpeedDicOfTpperception: make(map[uint32]float64),
- } // /cicv_location
- mutexOfCicvLocation sync.RWMutex
- // /tpperception
- mutexOfTpperception sync.RWMutex
- // /pj_control_pub
- mutexOfPjControlPub sync.RWMutex
- // /data_read
- mutexOfDataRead sync.RWMutex
- // /pj_vehicle_fdb_pub
- mutexOfPjVehicleFdbPub sync.RWMutex
- // /pj_vehicle_fdb_pub
- mutexOfCicvAmrTrajectory sync.RWMutex
- )
- // PrepareTimeWindowProducerQueue 负责监听所有主题并修改时间窗口
- func PrepareTimeWindowProducerQueue() {
- c_log.GlobalLogger.Info("订阅者 goroutine,启动。")
- var err error
- subscribers := make([]*goroslib.Subscriber, len(commonConfig.SubscribeTopics))
- subscribersTimes := make([]time.Time, len(commonConfig.SubscribeTopics))
- subscribersTimeMutexes := make([]sync.Mutex, len(commonConfig.SubscribeTopics))
- subscribersMutexes := make([]sync.Mutex, len(commonConfig.SubscribeTopics))
- for i, topic := range commonConfig.SubscribeTopics {
- // 增加了可扩展性
- if topic == masterConfig.TopicOfCicvExtend {
- go func() {
- for {
- time.Sleep(time.Duration(3500) * time.Millisecond)
- for _, f := range masterConfig.RuleOfCicvExtend {
- label := f(pjisuvParam)
- if label != "" {
- saveTimeWindow(label, util.GetNowTimeCustom(), commonEntity.GetLastTimeWindow())
- break
- }
- }
- }
- }()
- }
- // 其他常规监听器
- 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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- for _, f := range masterConfig.RuleOfCicvAmrTrajectory {
- faultLabel = f(data, pjisuvParam)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- break
- }
- }
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // 触发后更新共享变量
- mutexOfCicvAmrTrajectory.RLock()
- {
- var currentCurvateres []float64
- for _, point := range data.Trajectoryinfo.Trajectorypoints {
- currentCurvateres = append(currentCurvateres, math.Abs(float64(point.Curvature)))
- }
- pjisuvParam.LastCurvaturesOfCicvAmrTrajectory = currentCurvateres
- }
- mutexOfCicvAmrTrajectory.RUnlock()
- },
- })
- }
- // 12
- if topic == masterConfig.TopicOfCicvLocation && (len(masterConfig.RuleOfCicvLocation1) > 0 || len(masterConfig.RuleOfCicvLocation2) > 0) {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *pjisuv_msgs.PerceptionLocalization) {
- // 更新共享变量
- mutexOfCicvLocation.RLock()
- {
- pjisuvParam.VelocityXOfCicvLocation = data.VelocityX
- pjisuvParam.VelocityYOfCicvLocation = data.VelocityY
- pjisuvParam.VelocityZOfCicvLocation = data.VelocityZ
- pjisuvParam.YawOfCicvLocation = data.Yaw
- pjisuvParam.AngularVelocityZOfCicvLocation = data.AngularVelocityZ
- pjisuvParam.PositionXOfCicvLocation = data.PositionX
- pjisuvParam.PositionYOfCicvLocation = data.PositionY
- }
- mutexOfCicvLocation.RUnlock()
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCicvLocation1) > 0 {
- for _, f := range masterConfig.RuleOfCicvLocation1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- break
- }
- }
- }
- if faultLabel == "" && len(masterConfig.RuleOfCicvLocation2) > 0 {
- for _, f := range masterConfig.RuleOfCicvLocation2 {
- faultLabel = f(data, pjisuvParam)
- 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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- for _, f := range masterConfig.RuleOfMapPolygon {
- faultLabel = f(data, pjisuvParam)
- 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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- // 更新共享变量
- mutexOfPjControlPub.RLock()
- {
- pjisuvParam.NumCountPjiControlCommandOfPjControlPub++
- if pjisuvParam.NumCountPjiControlCommandOfPjControlPub == 10 {
- pjisuvParam.EgoSteeringCmdOfPjControlPub = append(pjisuvParam.EgoSteeringCmdOfPjControlPub, data.ICPVCmdStrAngle)
- pjisuvParam.EgoThrottleCmdOfPjControlPub = append(pjisuvParam.EgoThrottleCmdOfPjControlPub, data.ICPVCmdAccPelPosAct)
- pjisuvParam.NumCountPjiControlCommandOfPjControlPub = 0
- }
- }
- mutexOfPjControlPub.RUnlock()
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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()
- },
- })
- }
- // 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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- 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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- for _, f := range masterConfig.RuleOfTf {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- break
- }
- }
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 30
- if topic == masterConfig.TopicOfTpperception && len(masterConfig.RuleOfTpperception) > 0 {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *pjisuv_msgs.PerceptionObjects) {
- // 更新共享变量
- mutexOfTpperception.RLock()
- {
- for _, obj := range data.Objs {
- if obj.X <= 5 || math.Abs(float64(obj.Y)) >= 10 {
- continue
- }
- // 检查 ObjDicOfTpperception 是否为 nil,如果是,则初始化它
- if pjisuvParam.ObjDicOfTpperception == nil {
- pjisuvParam.ObjDicOfTpperception = make(map[uint32][]float32)
- }
- if _, ok := pjisuvParam.ObjDicOfTpperception[obj.Id]; !ok {
- pjisuvParam.ObjDicOfTpperception[obj.Id] = []float32{}
- }
- pjisuvParam.ObjDicOfTpperception[obj.Id] = append(pjisuvParam.ObjDicOfTpperception[obj.Id], obj.Y)
- }
- }
- mutexOfTpperception.RUnlock()
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- for _, f := range masterConfig.RuleOfTpperception {
- faultLabel = f(data, pjisuvParam)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- break
- }
- }
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // -------- 触发后更新共享变量
- mutexOfTpperception.RLock()
- {
- for _, obj := range data.Objs {
- pjisuvParam.ObjTypeDicOfTpperception[obj.Id] = obj.Type
- pjisuvParam.ObjSpeedDicOfTpperception[obj.Id] = math.Pow(math.Pow(float64(obj.Vxabs), 2)+math.Pow(float64(obj.Vyabs), 2), 0.5)
- }
- }
- mutexOfTpperception.RUnlock()
- },
- })
- }
- // 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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.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.TopicOfCameraImage && len(masterConfig.RuleOfCameraImage) > 0 {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *sensor_msgs.Image) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- for _, f := range masterConfig.RuleOfCameraImage {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- break
- }
- }
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 36
- if topic == masterConfig.TopicOfDataRead && len(masterConfig.RuleOfDataRead) > 0 {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *pjisuv_msgs.Retrieval) {
- // 更新共享变量
- mutexOfDataRead.RLock()
- {
- pjisuvParam.NumCountDataReadOfDataRead++
- if pjisuvParam.NumCountDataReadOfDataRead == 10 {
- pjisuvParam.EgoSteeringRealOfDataRead = append(pjisuvParam.EgoSteeringRealOfDataRead, data.ActStrWhAng)
- pjisuvParam.EgoThrottleRealOfDataRead = append(pjisuvParam.EgoThrottleRealOfDataRead, data.AccPed2)
- pjisuvParam.NumCountDataReadOfDataRead = 0
- }
- pjisuvParam.StrgAngleRealValueOfDataRead = data.ActStrWhAng
- }
- mutexOfDataRead.RUnlock()
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- for _, f := range masterConfig.RuleOfDataRead {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- break
- }
- }
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 37
- if topic == masterConfig.TopicOfPjiGps && len(masterConfig.RuleOfPjiGps) > 0 {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *pjisuv_msgs.PerceptionLocalization) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- for _, f := range masterConfig.RuleOfPjiGps {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- break
- }
- }
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 39
- if topic == masterConfig.TopicOfPjVehicleFdbPub && len(masterConfig.RuleOfPjVehicleFdbPub) > 0 {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *pjisuv_msgs.VehicleFdb) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > 1 {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- var faultLabel string
- for _, f := range masterConfig.RuleOfPjVehicleFdbPub {
- faultLabel = f(data, &pjisuvParam)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- break
- }
- }
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- if err != nil {
- c_log.GlobalLogger.Info("创建订阅者报错:", err)
- //TODO 如何回传日志
- continue
- }
- }
- select {
- case signal := <-service.ChannelKillWindowProducer:
- if signal == 1 {
- commonConfig.RosNode.Close()
- service.AddKillTimes("3")
- return
- }
- }
- }
- func saveTimeWindow(faultLabel string, faultHappenTime string, lastTimeWindow *commonEntity.TimeWindow) {
- masterTopics, slaveTopics := getTopicsOfNode(faultLabel)
- if lastTimeWindow == nil || util.TimeCustom1GreaterTimeCustom2(faultHappenTime, lastTimeWindow.TimeWindowEnd) { // 如果是不在旧故障窗口内,添加一个新窗口
- newTimeWindow := commonEntity.TimeWindow{
- FaultTime: faultHappenTime,
- TimeWindowBegin: util.TimeCustomChange(faultHappenTime, -commonConfig.PlatformConfig.TaskBeforeTime),
- TimeWindowEnd: util.TimeCustomChange(faultHappenTime, commonConfig.PlatformConfig.TaskAfterTime),
- Length: commonConfig.PlatformConfig.TaskBeforeTime + commonConfig.PlatformConfig.TaskAfterTime + 1,
- Labels: []string{faultLabel},
- MasterTopics: masterTopics,
- SlaveTopics: slaveTopics,
- }
- c_log.GlobalLogger.Infof("不在旧故障窗口内,向生产者队列添加一个新窗口,【Lable】=%v,【FaultTime】=%v,【Length】=%v", newTimeWindow.Labels, newTimeWindow.FaultTime, newTimeWindow.Length)
- commonEntity.AddTimeWindowToTimeWindowProducerQueue(newTimeWindow)
- } else { // 如果在旧故障窗口内
- commonEntity.TimeWindowProducerQueueMutex.RLock()
- defer commonEntity.TimeWindowProducerQueueMutex.RUnlock()
- // 更新故障窗口end时间
- maxEnd := util.TimeCustomChange(lastTimeWindow.TimeWindowBegin, commonConfig.PlatformConfig.TaskMaxTime)
- expectEnd := util.TimeCustomChange(faultHappenTime, commonConfig.PlatformConfig.TaskAfterTime)
- if util.TimeCustom1GreaterTimeCustom2(expectEnd, maxEnd) {
- lastTimeWindow.TimeWindowEnd = maxEnd
- lastTimeWindow.Length = commonConfig.PlatformConfig.TaskMaxTime
- } else {
- if util.TimeCustom1GreaterTimeCustom2(expectEnd, lastTimeWindow.TimeWindowEnd) {
- lastTimeWindow.TimeWindowEnd = expectEnd
- lastTimeWindow.Length = util.CalculateDifferenceOfTimeCustom(lastTimeWindow.TimeWindowBegin, expectEnd)
- }
- }
- // 更新label
- labels := lastTimeWindow.Labels
- lastTimeWindow.Labels = util.AppendIfNotExists(labels, faultLabel)
- // 更新 topic
- sourceMasterTopics := lastTimeWindow.MasterTopics
- lastTimeWindow.MasterTopics = util.MergeSlice(sourceMasterTopics, masterTopics)
- sourceSlaveTopics := lastTimeWindow.SlaveTopics
- lastTimeWindow.SlaveTopics = util.MergeSlice(sourceSlaveTopics, slaveTopics)
- c_log.GlobalLogger.Infof("在旧故障窗口内,更新生产者队列最新的窗口,【Lable】=%v,【FaultTime】=%v,【Length】=%v", lastTimeWindow.Labels, lastTimeWindow.FaultTime, lastTimeWindow.Length)
- }
- }
- func getTopicsOfNode(faultLabel string) (masterTopics []string, slaveTopics []string) {
- // 获取所有需要采集的topic
- var faultCodeTopics []string
- for _, code := range commonConfig.CloudConfig.Triggers {
- if code.Label == faultLabel {
- faultCodeTopics = code.Topics
- }
- }
- // 根据不同节点采集的topic进行分配采集
- for _, acceptTopic := range faultCodeTopics {
- for _, host := range commonConfig.CloudConfig.Hosts {
- for _, topic := range host.Topics {
- if host.Name == commonConfig.CloudConfig.Hosts[0].Name && acceptTopic == topic {
- masterTopics = append(masterTopics, acceptTopic)
- }
- if host.Name == commonConfig.CloudConfig.Hosts[1].Name && acceptTopic == topic {
- slaveTopics = append(slaveTopics, acceptTopic)
- }
- }
- }
- }
- return masterTopics, slaveTopics
- }
|