1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837183818391840184118421843184418451846184718481849185018511852185318541855185618571858185918601861186218631864186518661867186818691870187118721873187418751876187718781879188018811882188318841885188618871888188918901891189218931894189518961897189818991900190119021903190419051906190719081909191019111912191319141915191619171918191919201921192219231924192519261927192819291930193119321933193419351936193719381939194019411942194319441945194619471948194919501951195219531954195519561957195819591960196119621963196419651966196719681969197019711972197319741975197619771978197919801981198219831984198519861987198819891990199119921993199419951996199719981999200020012002200320042005200620072008200920102011201220132014201520162017201820192020202120222023202420252026202720282029203020312032203320342035203620372038203920402041204220432044204520462047204820492050205120522053205420552056205720582059206020612062206320642065206620672068206920702071207220732074207520762077207820792080208120822083208420852086208720882089209020912092 |
- 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
- GearPosSlice = []int16{}
- // --------------------------------------------------
- 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, masterConfig.AllTopicsNumber)
- subscribersTimes := make([]time.Time, masterConfig.AllTopicsNumber)
- subscribersTimeMutexes := make([]sync.Mutex, masterConfig.AllTopicsNumber)
- subscribersMutexes := make([]sync.Mutex, masterConfig.AllTopicsNumber)
- for i, topic := range masterConfig.AllTopics {
- 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:
- }
- }
- }()
- }
- create := false // 判断是否创建成功,用于打印日志
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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)
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- // 更新共享变量
- AbsSpeed := math.Sqrt(math.Pow(data.VelocityX, 2) + math.Pow(data.VelocityY, 2))
- AccelXSlice = append(AccelXSlice, data.AccelX)
- shareVars.Store("AbsSpeed", AbsSpeed)
- 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()
- }
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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)
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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 math.Abs(float64(obj.X)) >= 30 || math.Abs(float64(obj.Y)) >= 30 {
- 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))
- ObjDicOfTpperception[obj.Id][4] = append(ObjDicOfTpperception[obj.Id][4], obj.Heading)
- 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)
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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
- }
- GearPosSlice = append(GearPosSlice, data.GearPos)
- shareVars.Store("NumCountDataReadOfDataRead", numCountDataReadOfDataRead)
- shareVars.Store("EgoSteeringRealOfDataRead", egoSteeringRealOfDataRead)
- shareVars.Store("EgoThrottleRealOfDataRead", egoThrottleRealOfDataRead)
- shareVars.Store("ActStrWhAngOfDataRead", data.ActStrWhAng)
- shareVars.Store("GearPosSlice", GearPosSlice)
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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()
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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)
- },
- })
- if err == nil {
- create = true
- }
- }
- // 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 {
- create = true
- }
- }
- if err != nil {
- c_log.GlobalLogger.Infof("创建订阅者报错,可能由于节点未启动,再次尝试【%v】", err)
- time.Sleep(time.Duration(2) * time.Second)
- continue
- } else {
- if create {
- c_log.GlobalLogger.Infof("创建订阅者订阅话题【%v】", topic)
- }
- break
- }
- }
- }
- c_log.GlobalLogger.Infof("全部订阅者创建完成。")
- 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
- }
|