123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968 |
- 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)
- shareVars.Store("Latitude", data.Latitude)
- shareVars.Store("Longitude", data.Longitude)
- // 用于判断是否在车间内
- 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)
- absspeed := math.Sqrt(math.Pow(float64(obj.Vxabs), 2) + math.Pow(float64(obj.Vyabs), 2))
- ObjDicOfTpperception[obj.Id][3] = append(ObjDicOfTpperception[obj.Id][3], float32(absspeed))
- 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
- }
|