12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964 |
- 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_ticker"
- "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"
- )
- 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()
- // -----------------------------共享变量
- //cicv_location
- AccelXSlice = []float64{}
- // /tpperception
- ObjDicOfTpperception = make(map[uint32][][]float32)
- objTypeDicOfTpperception = make(map[uint32]uint8)
- objSpeedDicOfTpperception = make(map[uint32]float64)
- // /pji_control_pub
- numCountPjiControlCommandOfPjControlPub int
- egoSteeringCmdOfPjControlPub []float64
- egoThrottleCmdOfPjControlPub []float64
- // /data_read
- numCountDataReadOfDataRead int
- egoSteeringRealOfDataRead []float64
- egoThrottleRealOfDataRead []float64
- // --------------------------------------------------
- shareVars = new(sync.Map)
- saveTimeWindowMutex sync.Mutex // 保存时间窗口需要锁,防止数据竟态
- latestTimeWindowEnd = util.GetTimeCustom(time.Now())
- triggerInterval = 3.0 // 每个触发器3秒触发一次
- )
- // 负责监听所有主题并修改时间窗口
- func ProduceWindow() {
- 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 {
- for {
- // 定时器,区别于订阅者
- if topic == pjisuv_ticker.TickerTopic {
- // 1 把所有触发器函数执行一遍,触发器内部创建额外的定时任务goroutine
- for _, f := range masterConfig.RuleOfCicvTicker {
- f(shareVars)
- }
- // 2 创建goroutine接收定时任务触发器返回的Label和Time,执行触发逻辑
- go func() {
- for {
- time.Sleep(time.Duration(1)) // 降低循环频率
- select {
- case tickInfo := <-pjisuv_ticker.TickerChan:
- faultLabel := tickInfo.FaultLabel
- faultHappenTime := tickInfo.FaultHappenTime
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- default:
- }
- }
- }()
- }
- // 其他常规监听器
- c_log.GlobalLogger.Info("创建订阅者订阅话题:" + topic)
- // 1
- if topic == masterConfig.TopicOfAmrPose && (len(masterConfig.RuleOfAmrPose1) > 0 || len(masterConfig.RuleOfAmrPose3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfAmrPose1) > 0 {
- for _, f := range masterConfig.RuleOfAmrPose1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfAmrPose3) > 0 {
- for _, f := range masterConfig.RuleOfAmrPose3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 2
- if topic == masterConfig.TopicOfBoundingBoxesFast &&
- (len(masterConfig.RuleOfBoundingBoxesFast1) > 0 ||
- len(masterConfig.RuleOfBoundingBoxesFast3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfBoundingBoxesFast1) > 0 {
- for _, f := range masterConfig.RuleOfBoundingBoxesFast1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfBoundingBoxesFast3) > 0 {
- for _, f := range masterConfig.RuleOfBoundingBoxesFast3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 3
- if topic == masterConfig.TopicOfCameraFault &&
- (len(masterConfig.RuleOfCameraFault1) > 0 ||
- len(masterConfig.RuleOfCameraFault3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCameraFault1) > 0 {
- for _, f := range masterConfig.RuleOfCameraFault1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCameraFault3) > 0 {
- for _, f := range masterConfig.RuleOfCameraFault3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 4
- if topic == masterConfig.TopicOfCanData &&
- (len(masterConfig.RuleOfCanData1) > 0 ||
- len(masterConfig.RuleOfCanData3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCanData1) > 0 {
- for _, f := range masterConfig.RuleOfCanData1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCanData3) > 0 {
- for _, f := range masterConfig.RuleOfCanData3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 5
- if topic == masterConfig.TopicOfCh128x1LslidarPointCloud &&
- (len(masterConfig.RuleOfCh128x1LslidarPointCloud1) > 0 ||
- len(masterConfig.RuleOfCh128x1LslidarPointCloud3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCh128x1LslidarPointCloud1) > 0 {
- for _, f := range masterConfig.RuleOfCh128x1LslidarPointCloud1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCh128x1LslidarPointCloud3) > 0 {
- for _, f := range masterConfig.RuleOfCh128x1LslidarPointCloud3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 6
- if topic == masterConfig.TopicOfCh64wLLslidarPointCloud &&
- (len(masterConfig.RuleOfCh64wLLslidarPointCloud1) > 0 ||
- len(masterConfig.RuleOfCh64wLLslidarPointCloud3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCh64wLLslidarPointCloud1) > 0 {
- for _, f := range masterConfig.RuleOfCh64wLLslidarPointCloud1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCh64wLLslidarPointCloud3) > 0 {
- for _, f := range masterConfig.RuleOfCh64wLLslidarPointCloud3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 7
- if topic == masterConfig.TopicOfCh64wLScan &&
- (len(masterConfig.RuleOfCh64wLScan1) > 0 ||
- len(masterConfig.RuleOfCh64wLScan3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCh64wLScan1) > 0 {
- for _, f := range masterConfig.RuleOfCh64wLScan1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCh64wLScan3) > 0 {
- for _, f := range masterConfig.RuleOfCh64wLScan3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 8
- if topic == masterConfig.TopicOfCh64wRLslidarPointCloud &&
- (len(masterConfig.RuleOfCh64wRLslidarPointCloud1) > 0 ||
- len(masterConfig.RuleOfCh64wRLslidarPointCloud3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCh64wRLslidarPointCloud1) > 0 {
- for _, f := range masterConfig.RuleOfCh64wRLslidarPointCloud1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCh64wRLslidarPointCloud3) > 0 {
- for _, f := range masterConfig.RuleOfCh64wRLslidarPointCloud3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 9
- if topic == masterConfig.TopicOfCh64wRScan &&
- (len(masterConfig.RuleOfCh64wRScan1) > 0 ||
- len(masterConfig.RuleOfCh64wRScan3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCh64wRScan1) > 0 {
- for _, f := range masterConfig.RuleOfCh64wRScan1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCh64wRScan3) > 0 {
- for _, f := range masterConfig.RuleOfCh64wRScan3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 10
- if topic == masterConfig.TopicOfCicvLidarclusterMovingObjects &&
- (len(masterConfig.RuleOfCicvLidarclusterMovingObjects1) > 0 ||
- len(masterConfig.RuleOfCicvLidarclusterMovingObjects3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCicvLidarclusterMovingObjects1) > 0 {
- for _, f := range masterConfig.RuleOfCicvLidarclusterMovingObjects1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCicvLidarclusterMovingObjects3) > 0 {
- for _, f := range masterConfig.RuleOfCicvLidarclusterMovingObjects3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 11 有共享变量的订阅者必须被创建
- if topic == masterConfig.TopicOfCicvAmrTrajectory {
- 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCicvAmrTrajectory1) > 0 {
- for _, f := range masterConfig.RuleOfCicvAmrTrajectory1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCicvAmrTrajectory3) > 0 {
- for _, f := range masterConfig.RuleOfCicvAmrTrajectory3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // 更新共享变量
- currentCurvateres := make([]float64, 0)
- for _, point := range data.Trajectoryinfo.Trajectorypoints {
- currentCurvateres = append(currentCurvateres, math.Abs(float64(point.Curvature)))
- }
- shareVars.Store("LastCurvaturesOfCicvAmrTrajectory", currentCurvateres)
- shareVars.Store("DecisionType", data.Trajectoryinfo.DecisionType)
- },
- })
- }
- // 12 有共享变量的订阅者必须被创建
- if topic == masterConfig.TopicOfCicvLocation {
- 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() > triggerInterval {
- 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)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCicvLocation3) > 0 {
- for _, f := range masterConfig.RuleOfCicvLocation3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // 更新共享变量
- AbsAccel := math.Sqrt(math.Pow(data.AccelX, 2) + math.Pow(data.AccelY, 2))
- AccelXSlice = append(AccelXSlice, AbsAccel)
- shareVars.Store("AccelXSlice", AccelXSlice)
- shareVars.Store("VelocityXOfCicvLocation", data.VelocityX)
- shareVars.Store("VelocityYOfCicvLocation", data.VelocityY)
- shareVars.Store("VelocityZOfCicvLocation", data.VelocityZ)
- shareVars.Store("YawOfCicvLocation", data.Yaw)
- shareVars.Store("AngularVelocityZOfCicvLocation", data.AngularVelocityZ)
- shareVars.Store("PositionXOfCicvLocation", data.PositionX)
- shareVars.Store("PositionYOfCicvLocation", data.PositionY)
- // 用于判断是否在车间内
- if time.Since(cicvLocationTime).Seconds() > 1 {
- p := Point{x: data.PositionX, y: data.PositionY}
- OutsideWorkshopFlag := isPointInPolygon(p, vertices) //在车间返回0,不在车间返回1
- shareVars.Store("OutsideWorkshopFlag", OutsideWorkshopFlag)
- cicvLocationTime = time.Now()
- }
- },
- })
- }
- // 13
- if topic == masterConfig.TopicOfCloudClusters &&
- (len(masterConfig.RuleOfCloudClusters1) > 0 ||
- len(masterConfig.RuleOfCloudClusters3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCloudClusters1) > 0 {
- for _, f := range masterConfig.RuleOfCloudClusters1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCloudClusters3) > 0 {
- for _, f := range masterConfig.RuleOfCloudClusters3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 14
- if topic == masterConfig.TopicOfHeartbeatInfo &&
- (len(masterConfig.RuleOfHeartbeatInfo1) > 0 ||
- len(masterConfig.RuleOfHeartbeatInfo3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfHeartbeatInfo1) > 0 {
- for _, f := range masterConfig.RuleOfHeartbeatInfo1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfHeartbeatInfo3) > 0 {
- for _, f := range masterConfig.RuleOfHeartbeatInfo3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 15
- if topic == masterConfig.TopicOfLidarPretreatmentCost &&
- (len(masterConfig.RuleOfLidarPretreatmentCost1) > 0 ||
- len(masterConfig.RuleOfLidarPretreatmentCost3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfLidarPretreatmentCost1) > 0 {
- for _, f := range masterConfig.RuleOfLidarPretreatmentCost1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfLidarPretreatmentCost3) > 0 {
- for _, f := range masterConfig.RuleOfLidarPretreatmentCost3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 16
- if topic == masterConfig.TopicOfLidarPretreatmentOdometry &&
- (len(masterConfig.RuleOfLidarPretreatmentOdometry1) > 0 ||
- len(masterConfig.RuleOfLidarPretreatmentOdometry3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfLidarPretreatmentOdometry1) > 0 {
- for _, f := range masterConfig.RuleOfLidarPretreatmentOdometry1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfLidarPretreatmentOdometry3) > 0 {
- for _, f := range masterConfig.RuleOfLidarPretreatmentOdometry3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 17
- if topic == masterConfig.TopicOfLidarRoi &&
- (len(masterConfig.RuleOfLidarRoi1) > 0 ||
- len(masterConfig.RuleOfLidarRoi3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfLidarRoi1) > 0 {
- for _, f := range masterConfig.RuleOfLidarRoi1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfLidarRoi3) > 0 {
- for _, f := range masterConfig.RuleOfLidarRoi3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 18
- if topic == masterConfig.TopicOfLine1 &&
- (len(masterConfig.RuleOfLine11) > 0 ||
- len(masterConfig.RuleOfLine13) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfLine11) > 0 {
- for _, f := range masterConfig.RuleOfLine11 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfLine13) > 0 {
- for _, f := range masterConfig.RuleOfLine13 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 19
- if topic == masterConfig.TopicOfLine2 &&
- (len(masterConfig.RuleOfLine21) > 0 ||
- len(masterConfig.RuleOfLine23) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfLine21) > 0 {
- for _, f := range masterConfig.RuleOfLine21 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfLine23) > 0 {
- for _, f := range masterConfig.RuleOfLine23 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 20
- if topic == masterConfig.TopicOfMapPolygon &&
- (len(masterConfig.RuleOfMapPolygon1) > 0 ||
- len(masterConfig.RuleOfMapPolygon3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfMapPolygon1) > 0 {
- for _, f := range masterConfig.RuleOfMapPolygon1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfMapPolygon3) > 0 {
- for _, f := range masterConfig.RuleOfMapPolygon3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 21
- if topic == masterConfig.TopicOfObstacleDisplay &&
- (len(masterConfig.RuleOfObstacleDisplay1) > 0 ||
- len(masterConfig.RuleOfObstacleDisplay3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfObstacleDisplay1) > 0 {
- for _, f := range masterConfig.RuleOfObstacleDisplay1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfObstacleDisplay3) > 0 {
- for _, f := range masterConfig.RuleOfObstacleDisplay3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 22 有共享变量的订阅者必须被创建
- if topic == masterConfig.TopicOfPjControlPub {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *pjisuv_msgs.CommonVehicleCmd) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfPjControlPub1) > 0 {
- for _, f := range masterConfig.RuleOfPjControlPub1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfPjControlPub3) > 0 {
- for _, f := range masterConfig.RuleOfPjControlPub3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // 更新共享变量
- numCountPjiControlCommandOfPjControlPub++
- if numCountPjiControlCommandOfPjControlPub == 10 {
- egoSteeringCmdOfPjControlPub = append(egoSteeringCmdOfPjControlPub, data.ICPVCmdStrAngle)
- egoThrottleCmdOfPjControlPub = append(egoThrottleCmdOfPjControlPub, data.ICPVCmdAccPelPosAct)
- numCountPjiControlCommandOfPjControlPub = 0
- }
- shareVars.Store("NumCountPjiControlCommandOfPjControlPub", numCountPjiControlCommandOfPjControlPub)
- shareVars.Store("EgoSteeringCmdOfPjControlPub", egoSteeringCmdOfPjControlPub)
- shareVars.Store("EgoThrottleCmdOfPjControlPub", egoThrottleCmdOfPjControlPub)
- },
- })
- }
- // 23
- if topic == masterConfig.TopicOfPointsCluster &&
- (len(masterConfig.RuleOfPointsCluster1) > 0 ||
- len(masterConfig.RuleOfPointsCluster3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfPointsCluster1) > 0 {
- for _, f := range masterConfig.RuleOfPointsCluster1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfPointsCluster3) > 0 {
- for _, f := range masterConfig.RuleOfPointsCluster3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 24
- if topic == masterConfig.TopicOfPointsConcat &&
- (len(masterConfig.RuleOfPointsConcat1) > 0 ||
- len(masterConfig.RuleOfPointsConcat3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfPointsConcat1) > 0 {
- for _, f := range masterConfig.RuleOfPointsConcat1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfPointsConcat3) > 0 {
- for _, f := range masterConfig.RuleOfPointsConcat3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 25
- if topic == masterConfig.TopicOfReferenceDisplay &&
- (len(masterConfig.RuleOfReferenceDisplay1) > 0 ||
- len(masterConfig.RuleOfReferenceDisplay3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfReferenceDisplay1) > 0 {
- for _, f := range masterConfig.RuleOfReferenceDisplay1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfReferenceDisplay3) > 0 {
- for _, f := range masterConfig.RuleOfReferenceDisplay3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 26
- if topic == masterConfig.TopicOfReferenceTrajectory &&
- (len(masterConfig.RuleOfReferenceTrajectory1) > 0 ||
- len(masterConfig.RuleOfReferenceTrajectory3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfReferenceTrajectory1) > 0 {
- for _, f := range masterConfig.RuleOfReferenceTrajectory1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfReferenceTrajectory3) > 0 {
- for _, f := range masterConfig.RuleOfReferenceTrajectory3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 27
- if topic == masterConfig.TopicOfRoiPoints &&
- (len(masterConfig.RuleOfRoiPoints1) > 0 ||
- len(masterConfig.RuleOfRoiPoints3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfRoiPoints1) > 0 {
- for _, f := range masterConfig.RuleOfRoiPoints1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfRoiPoints3) > 0 {
- for _, f := range masterConfig.RuleOfRoiPoints3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 28
- if topic == masterConfig.TopicOfRoiPolygon &&
- (len(masterConfig.RuleOfRoiPolygon1) > 0 ||
- len(masterConfig.RuleOfRoiPolygon3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfRoiPolygon1) > 0 {
- for _, f := range masterConfig.RuleOfRoiPolygon1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfRoiPolygon3) > 0 {
- for _, f := range masterConfig.RuleOfRoiPolygon3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 29
- if topic == masterConfig.TopicOfTf &&
- (len(masterConfig.RuleOfTf1) > 0 ||
- len(masterConfig.RuleOfTf3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfTf1) > 0 {
- for _, f := range masterConfig.RuleOfTf1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfTf3) > 0 {
- for _, f := range masterConfig.RuleOfTf3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 30 有共享变量的订阅者必须被创建
- if topic == masterConfig.TopicOfTpperception {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *pjisuv_msgs.PerceptionObjects) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfTpperception1) > 0 {
- for _, f := range masterConfig.RuleOfTpperception1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfTpperception3) > 0 {
- for _, f := range masterConfig.RuleOfTpperception3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // 更新共享变量
- for _, obj := range data.Objs {
- if obj.X <= 5 || math.Abs(float64(obj.Y)) >= 10 {
- continue
- }
- if _, ok := ObjDicOfTpperception[obj.Id]; !ok {
- ObjDicOfTpperception[obj.Id] = [][]float32{{}, {}, {}, {}}
- }
- ObjDicOfTpperception[obj.Id][0] = append(ObjDicOfTpperception[obj.Id][0], obj.X)
- ObjDicOfTpperception[obj.Id][1] = append(ObjDicOfTpperception[obj.Id][1], obj.Y)
- ObjDicOfTpperception[obj.Id][2] = append(ObjDicOfTpperception[obj.Id][2], obj.Vxrel)
- ObjDicOfTpperception[obj.Id][3] = append(ObjDicOfTpperception[obj.Id][3], obj.Vxabs)
- objTypeDicOfTpperception[obj.Id] = obj.Type
- objSpeedDicOfTpperception[obj.Id] = math.Pow(math.Pow(float64(obj.Vxabs), 2)+math.Pow(float64(obj.Vyabs), 2), 0.5)
- }
- shareVars.Store("ObjDicOfTpperception", ObjDicOfTpperception)
- shareVars.Store("ObjTypeDicOfTpperception", objTypeDicOfTpperception)
- shareVars.Store("ObjSpeedDicOfTpperception", objSpeedDicOfTpperception)
- },
- })
- }
- // 31
- if topic == masterConfig.TopicOfTpperceptionVis &&
- (len(masterConfig.RuleOfTpperceptionVis1) > 0 ||
- len(masterConfig.RuleOfTpperceptionVis3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfTpperceptionVis1) > 0 {
- for _, f := range masterConfig.RuleOfTpperceptionVis1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfTpperceptionVis3) > 0 {
- for _, f := range masterConfig.RuleOfTpperceptionVis3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 32
- if topic == masterConfig.TopicOfTprouteplan &&
- (len(masterConfig.RuleOfTprouteplan1) > 0 ||
- len(masterConfig.RuleOfTprouteplan3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfTprouteplan1) > 0 {
- for _, f := range masterConfig.RuleOfTprouteplan1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfTprouteplan3) > 0 {
- for _, f := range masterConfig.RuleOfTprouteplan3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 33
- if topic == masterConfig.TopicOfTrajectoryDisplay &&
- (len(masterConfig.RuleOfTrajectoryDisplay1) > 0 ||
- len(masterConfig.RuleOfTrajectoryDisplay3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfTrajectoryDisplay1) > 0 {
- for _, f := range masterConfig.RuleOfTrajectoryDisplay1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfTrajectoryDisplay3) > 0 {
- for _, f := range masterConfig.RuleOfTrajectoryDisplay3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 34
- if topic == masterConfig.TopicOfUngroundCloudpoints &&
- (len(masterConfig.RuleOfUngroundCloudpoints1) > 0 ||
- len(masterConfig.RuleOfUngroundCloudpoints3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfUngroundCloudpoints1) > 0 {
- for _, f := range masterConfig.RuleOfUngroundCloudpoints1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfUngroundCloudpoints3) > 0 {
- for _, f := range masterConfig.RuleOfUngroundCloudpoints3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 35
- if topic == masterConfig.TopicOfCameraImage &&
- (len(masterConfig.RuleOfCameraImage1) > 0 ||
- len(masterConfig.RuleOfCameraImage3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfCameraImage1) > 0 {
- for _, f := range masterConfig.RuleOfCameraImage1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfCameraImage3) > 0 {
- for _, f := range masterConfig.RuleOfCameraImage3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 36 有共享变量的订阅者必须被创建
- if topic == masterConfig.TopicOfDataRead {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *pjisuv_msgs.Retrieval) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfDataRead1) > 0 {
- for _, f := range masterConfig.RuleOfDataRead1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfDataRead3) > 0 {
- for _, f := range masterConfig.RuleOfDataRead3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // 更新共享变量
- numCountDataReadOfDataRead++
- if numCountDataReadOfDataRead == 10 {
- egoSteeringRealOfDataRead = append(egoSteeringRealOfDataRead, data.ActStrWhAng)
- egoThrottleRealOfDataRead = append(egoThrottleRealOfDataRead, data.AccPed2)
- numCountDataReadOfDataRead = 0
- }
- shareVars.Store("NumCountDataReadOfDataRead", numCountDataReadOfDataRead)
- shareVars.Store("EgoSteeringRealOfDataRead", egoSteeringRealOfDataRead)
- shareVars.Store("EgoThrottleRealOfDataRead", egoThrottleRealOfDataRead)
- shareVars.Store("ActStrWhAngOfDataRead", data.ActStrWhAng)
- },
- })
- }
- // 37
- if topic == masterConfig.TopicOfPjiGps &&
- (len(masterConfig.RuleOfPjiGps1) > 0 ||
- len(masterConfig.RuleOfPjiGps3) > 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfPjiGps1) > 0 {
- for _, f := range masterConfig.RuleOfPjiGps1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfPjiGps3) > 0 {
- for _, f := range masterConfig.RuleOfPjiGps3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- },
- })
- }
- // 39 有共享变量的订阅者必须被创建
- if topic == masterConfig.TopicOfPjVehicleFdbPub {
- 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() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfPjVehicleFdbPub1) > 0 {
- for _, f := range masterConfig.RuleOfPjVehicleFdbPub1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfPjVehicleFdbPub3) > 0 {
- for _, f := range masterConfig.RuleOfPjVehicleFdbPub3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // 更新共享变量
- shareVars.Store("AutomodeOfPjVehicleFdbPub", data.Automode)
- },
- })
- }
- // 40 有共享变量的订阅者必须被创建
- if topic == masterConfig.TopicOfEndPointMessage {
- subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
- Node: commonConfig.RosNode,
- Topic: topic,
- Callback: func(data *geometry_msgs.Point) {
- subscribersTimeMutexes[i].Lock()
- if time.Since(subscribersTimes[i]).Seconds() > triggerInterval {
- subscribersMutexes[i].Lock()
- faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
- lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
- faultLabel := ""
- if len(masterConfig.RuleOfEndPointMessage1) > 0 {
- for _, f := range masterConfig.RuleOfEndPointMessage1 {
- faultLabel = f(data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- if len(masterConfig.RuleOfEndPointMessage3) > 0 {
- for _, f := range masterConfig.RuleOfEndPointMessage3 {
- faultLabel = f(shareVars, data)
- if faultLabel != "" {
- saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
- subscribersTimes[i] = time.Now()
- goto TriggerSuccess
- }
- }
- }
- TriggerSuccess:
- subscribersMutexes[i].Unlock()
- }
- subscribersTimeMutexes[i].Unlock()
- // 更新共享变量
- shareVars.Store("EndPointX", data.X)
- shareVars.Store("EndPointY", data.Y)
- },
- })
- }
- if err != nil {
- c_log.GlobalLogger.Info("创建订阅者报错,可能由于节点未启动,再次尝试:", err)
- time.Sleep(time.Duration(2) * time.Second)
- continue
- } else {
- break
- }
- }
- }
- select {
- case signal := <-service.ChannelKillWindowProducer:
- if signal == 1 {
- commonConfig.RosNode.Close()
- service.AddKillTimes("3")
- return
- }
- }
- }
- func saveTimeWindow(faultLabel string, faultHappenTime string, lastTimeWindow *commonEntity.TimeWindow) {
- saveTimeWindowMutex.Lock()
- defer saveTimeWindowMutex.Unlock()
- masterTopics, slaveTopics := getTopicsOfNode(faultLabel)
- if lastTimeWindow == nil || util.TimeCustom1GreaterTimeCustom2(faultHappenTime, lastTimeWindow.TimeWindowEnd) { // 如果是不在旧故障窗口内,添加一个新窗口
- exceptBegin := util.TimeCustomChange(faultHappenTime, -commonConfig.PlatformConfig.TaskBeforeTime)
- finalTimeWindowBegin := ""
- if util.TimeCustom1LessEqualThanTimeCustom2(exceptBegin, latestTimeWindowEnd) { // 窗口最早时间不能早于上一个窗口结束时间
- finalTimeWindowBegin = latestTimeWindowEnd
- } else {
- finalTimeWindowBegin = exceptBegin
- }
- latestTimeWindowEnd = util.TimeCustomChange(faultHappenTime, commonConfig.PlatformConfig.TaskAfterTime)
- newTimeWindow := commonEntity.TimeWindow{
- FaultTime: faultHappenTime,
- TimeWindowBegin: finalTimeWindowBegin,
- TimeWindowEnd: latestTimeWindowEnd,
- Length: util.CalculateDifferenceOfTimeCustom(finalTimeWindowBegin, latestTimeWindowEnd),
- 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时间
- expectEnd := util.TimeCustomChange(faultHappenTime, commonConfig.PlatformConfig.TaskAfterTime) // 窗口期望关闭时间是触发时间加上后置时间
- expectLength := util.CalculateDifferenceOfTimeCustom(lastTimeWindow.TimeWindowBegin, expectEnd)
- if expectLength < commonConfig.PlatformConfig.TaskMaxTime {
- latestTimeWindowEnd = expectEnd
- lastTimeWindow.TimeWindowEnd = latestTimeWindowEnd
- lastTimeWindow.Length = util.CalculateDifferenceOfTimeCustom(lastTimeWindow.TimeWindowBegin, lastTimeWindow.TimeWindowEnd)
- }
- // 更新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
- }
- 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
- }
|