produce_window.go 47 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310
  1. package svc
  2. import (
  3. commonConfig "cicv-data-closedloop/aarch64/pjisuv/common/config"
  4. "cicv-data-closedloop/aarch64/pjisuv/common/service"
  5. masterConfig "cicv-data-closedloop/aarch64/pjisuv/master/package/config"
  6. "cicv-data-closedloop/common/config/c_log"
  7. "cicv-data-closedloop/common/entity"
  8. "cicv-data-closedloop/common/util"
  9. "cicv-data-closedloop/pjisuv_msgs"
  10. "github.com/bluenviron/goroslib/v2"
  11. "github.com/bluenviron/goroslib/v2/pkg/msgs/geometry_msgs"
  12. "github.com/bluenviron/goroslib/v2/pkg/msgs/nav_msgs"
  13. "github.com/bluenviron/goroslib/v2/pkg/msgs/sensor_msgs"
  14. "github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
  15. "github.com/bluenviron/goroslib/v2/pkg/msgs/tf2_msgs"
  16. "github.com/bluenviron/goroslib/v2/pkg/msgs/visualization_msgs"
  17. "sync"
  18. "time"
  19. )
  20. var (
  21. m sync.RWMutex
  22. velocityX float64
  23. velocityY float64
  24. yaw float64
  25. )
  26. // PrepareTimeWindowProducerQueue 负责监听所有主题并修改时间窗口
  27. func PrepareTimeWindowProducerQueue() {
  28. c_log.GlobalLogger.Info("订阅者 goroutine,启动。")
  29. var err error
  30. subscribers := make([]*goroslib.Subscriber, len(commonConfig.SubscribeTopics))
  31. subscribersTimes := make([]time.Time, len(commonConfig.SubscribeTopics))
  32. subscribersTimeMutexes := make([]sync.Mutex, len(commonConfig.SubscribeTopics))
  33. subscribersMutexes := make([]sync.Mutex, len(commonConfig.SubscribeTopics))
  34. for i, topic := range commonConfig.SubscribeTopics {
  35. c_log.GlobalLogger.Info("创建订阅者订阅话题:" + topic)
  36. // 1
  37. if topic == masterConfig.TopicOfAmrPose && len(masterConfig.RuleOfAmrPose) > 0 {
  38. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  39. Node: commonConfig.RosNode,
  40. Topic: topic,
  41. Callback: func(data *visualization_msgs.MarkerArray) {
  42. subscribersTimeMutexes[i].Lock()
  43. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  44. subscribersMutexes[i].Lock()
  45. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  46. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  47. var faultLabel string
  48. for _, f := range masterConfig.RuleOfAmrPose {
  49. faultLabel = f(data)
  50. if faultLabel != "" {
  51. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  52. subscribersTimes[i] = time.Now()
  53. break
  54. }
  55. }
  56. subscribersMutexes[i].Unlock()
  57. }
  58. subscribersTimeMutexes[i].Unlock()
  59. },
  60. })
  61. }
  62. // 2
  63. if topic == masterConfig.TopicOfBoundingBoxesFast && len(masterConfig.RuleOfBoundingBoxesFast) > 0 {
  64. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  65. Node: commonConfig.RosNode,
  66. Topic: topic,
  67. Callback: func(data *pjisuv_msgs.BoundingBoxArray) {
  68. subscribersTimeMutexes[i].Lock()
  69. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  70. subscribersMutexes[i].Lock()
  71. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  72. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  73. var faultLabel string
  74. for _, f := range masterConfig.RuleOfBoundingBoxesFast {
  75. faultLabel = f(data)
  76. if faultLabel != "" {
  77. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  78. subscribersTimes[i] = time.Now()
  79. break
  80. }
  81. }
  82. subscribersMutexes[i].Unlock()
  83. }
  84. subscribersTimeMutexes[i].Unlock()
  85. },
  86. })
  87. }
  88. // 3
  89. if topic == masterConfig.TopicOfCameraFault && len(masterConfig.RuleOfCameraFault) > 0 {
  90. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  91. Node: commonConfig.RosNode,
  92. Topic: topic,
  93. Callback: func(data *pjisuv_msgs.FaultVec) {
  94. subscribersTimeMutexes[i].Lock()
  95. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  96. subscribersMutexes[i].Lock()
  97. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  98. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  99. var faultLabel string
  100. for _, f := range masterConfig.RuleOfCameraFault {
  101. faultLabel = f(data)
  102. if faultLabel != "" {
  103. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  104. subscribersTimes[i] = time.Now()
  105. break
  106. }
  107. }
  108. subscribersMutexes[i].Unlock()
  109. }
  110. subscribersTimeMutexes[i].Unlock()
  111. },
  112. })
  113. }
  114. // 4
  115. if topic == masterConfig.TopicOfCanData && len(masterConfig.RuleOfCanData) > 0 {
  116. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  117. Node: commonConfig.RosNode,
  118. Topic: topic,
  119. Callback: func(data *pjisuv_msgs.Frame) {
  120. subscribersTimeMutexes[i].Lock()
  121. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  122. subscribersMutexes[i].Lock()
  123. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  124. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  125. var faultLabel string
  126. for _, f := range masterConfig.RuleOfCanData {
  127. faultLabel = f(data)
  128. if faultLabel != "" {
  129. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  130. subscribersTimes[i] = time.Now()
  131. break
  132. }
  133. }
  134. subscribersMutexes[i].Unlock()
  135. }
  136. subscribersTimeMutexes[i].Unlock()
  137. },
  138. })
  139. }
  140. // 5
  141. if topic == masterConfig.TopicOfCh128x1LslidarPointCloud && len(masterConfig.RuleOfCh128x1LslidarPointCloud) > 0 {
  142. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  143. Node: commonConfig.RosNode,
  144. Topic: topic,
  145. Callback: func(data *sensor_msgs.PointCloud2) {
  146. subscribersTimeMutexes[i].Lock()
  147. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  148. subscribersMutexes[i].Lock()
  149. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  150. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  151. var faultLabel string
  152. for _, f := range masterConfig.RuleOfCh128x1LslidarPointCloud {
  153. faultLabel = f(data)
  154. if faultLabel != "" {
  155. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  156. subscribersTimes[i] = time.Now()
  157. break
  158. }
  159. }
  160. subscribersMutexes[i].Unlock()
  161. }
  162. subscribersTimeMutexes[i].Unlock()
  163. },
  164. })
  165. }
  166. // 6
  167. if topic == masterConfig.TopicOfCh64wLLslidarPointCloud && len(masterConfig.RuleOfCh64wLLslidarPointCloud) > 0 {
  168. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  169. Node: commonConfig.RosNode,
  170. Topic: topic,
  171. Callback: func(data *sensor_msgs.PointCloud2) {
  172. subscribersTimeMutexes[i].Lock()
  173. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  174. subscribersMutexes[i].Lock()
  175. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  176. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  177. var faultLabel string
  178. for _, f := range masterConfig.RuleOfCh64wLLslidarPointCloud {
  179. faultLabel = f(data)
  180. if faultLabel != "" {
  181. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  182. subscribersTimes[i] = time.Now()
  183. break
  184. }
  185. }
  186. subscribersMutexes[i].Unlock()
  187. }
  188. subscribersTimeMutexes[i].Unlock()
  189. },
  190. })
  191. }
  192. // 7
  193. if topic == masterConfig.TopicOfCh64wLScan && len(masterConfig.RuleOfCh64wLScan) > 0 {
  194. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  195. Node: commonConfig.RosNode,
  196. Topic: topic,
  197. Callback: func(data *sensor_msgs.LaserScan) {
  198. subscribersTimeMutexes[i].Lock()
  199. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  200. subscribersMutexes[i].Lock()
  201. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  202. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  203. var faultLabel string
  204. for _, f := range masterConfig.RuleOfCh64wLScan {
  205. faultLabel = f(data)
  206. if faultLabel != "" {
  207. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  208. subscribersTimes[i] = time.Now()
  209. break
  210. }
  211. }
  212. subscribersMutexes[i].Unlock()
  213. }
  214. subscribersTimeMutexes[i].Unlock()
  215. },
  216. })
  217. }
  218. // 8
  219. if topic == masterConfig.TopicOfCh64wRLslidarPointCloud && len(masterConfig.RuleOfCh64wRLslidarPointCloud) > 0 {
  220. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  221. Node: commonConfig.RosNode,
  222. Topic: topic,
  223. Callback: func(data *sensor_msgs.PointCloud2) {
  224. subscribersTimeMutexes[i].Lock()
  225. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  226. subscribersMutexes[i].Lock()
  227. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  228. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  229. var faultLabel string
  230. for _, f := range masterConfig.RuleOfCh64wRLslidarPointCloud {
  231. faultLabel = f(data)
  232. if faultLabel != "" {
  233. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  234. subscribersTimes[i] = time.Now()
  235. break
  236. }
  237. }
  238. subscribersMutexes[i].Unlock()
  239. }
  240. subscribersTimeMutexes[i].Unlock()
  241. },
  242. })
  243. }
  244. // 9
  245. if topic == masterConfig.TopicOfCh64wRScan && len(masterConfig.RuleOfCh64wRScan) > 0 {
  246. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  247. Node: commonConfig.RosNode,
  248. Topic: topic,
  249. Callback: func(data *sensor_msgs.LaserScan) {
  250. subscribersTimeMutexes[i].Lock()
  251. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  252. subscribersMutexes[i].Lock()
  253. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  254. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  255. var faultLabel string
  256. for _, f := range masterConfig.RuleOfCh64wRScan {
  257. faultLabel = f(data)
  258. if faultLabel != "" {
  259. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  260. subscribersTimes[i] = time.Now()
  261. break
  262. }
  263. }
  264. subscribersMutexes[i].Unlock()
  265. }
  266. subscribersTimeMutexes[i].Unlock()
  267. },
  268. })
  269. }
  270. // 10
  271. if topic == masterConfig.TopicOfCicvLidarclusterMovingObjects && len(masterConfig.RuleOfCicvLidarclusterMovingObjects) > 0 {
  272. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  273. Node: commonConfig.RosNode,
  274. Topic: topic,
  275. Callback: func(data *pjisuv_msgs.PerceptionCicvMovingObjects) {
  276. subscribersTimeMutexes[i].Lock()
  277. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  278. subscribersMutexes[i].Lock()
  279. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  280. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  281. var faultLabel string
  282. for _, f := range masterConfig.RuleOfCicvLidarclusterMovingObjects {
  283. faultLabel = f(data)
  284. if faultLabel != "" {
  285. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  286. subscribersTimes[i] = time.Now()
  287. break
  288. }
  289. }
  290. subscribersMutexes[i].Unlock()
  291. }
  292. subscribersTimeMutexes[i].Unlock()
  293. },
  294. })
  295. }
  296. // 11
  297. if topic == masterConfig.TopicOfCicvAmrTrajectory && len(masterConfig.RuleOfCicvAmrTrajectory) > 0 {
  298. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  299. Node: commonConfig.RosNode,
  300. Topic: topic,
  301. Callback: func(data *pjisuv_msgs.Trajectory) {
  302. subscribersTimeMutexes[i].Lock()
  303. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  304. subscribersMutexes[i].Lock()
  305. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  306. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  307. var faultLabel string
  308. for _, f := range masterConfig.RuleOfCicvAmrTrajectory {
  309. faultLabel = f(data)
  310. if faultLabel != "" {
  311. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  312. subscribersTimes[i] = time.Now()
  313. break
  314. }
  315. }
  316. subscribersMutexes[i].Unlock()
  317. }
  318. subscribersTimeMutexes[i].Unlock()
  319. },
  320. })
  321. }
  322. // 12
  323. if topic == masterConfig.TopicOfCicvLocation && len(masterConfig.RuleOfCicvLocation) > 0 {
  324. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  325. Node: commonConfig.RosNode,
  326. Topic: topic,
  327. Callback: func(data *pjisuv_msgs.PerceptionLocalization) {
  328. // 更新共享变量
  329. m.RLock()
  330. velocityX = data.VelocityX
  331. velocityY = data.VelocityY
  332. yaw = data.Yaw
  333. m.RUnlock()
  334. subscribersTimeMutexes[i].Lock()
  335. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  336. subscribersMutexes[i].Lock()
  337. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  338. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  339. var faultLabel string
  340. for _, f := range masterConfig.RuleOfCicvLocation {
  341. faultLabel = f(data)
  342. if faultLabel != "" {
  343. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  344. break
  345. }
  346. }
  347. subscribersMutexes[i].Unlock()
  348. }
  349. subscribersTimeMutexes[i].Unlock()
  350. },
  351. })
  352. }
  353. // 13
  354. if topic == masterConfig.TopicOfCloudClusters && len(masterConfig.RuleOfCloudClusters) > 0 {
  355. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  356. Node: commonConfig.RosNode,
  357. Topic: topic,
  358. Callback: func(data *pjisuv_msgs.AutowareCloudClusterArray) {
  359. subscribersTimeMutexes[i].Lock()
  360. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  361. subscribersMutexes[i].Lock()
  362. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  363. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  364. var faultLabel string
  365. for _, f := range masterConfig.RuleOfCloudClusters {
  366. faultLabel = f(data)
  367. if faultLabel != "" {
  368. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  369. subscribersTimes[i] = time.Now()
  370. break
  371. }
  372. }
  373. subscribersMutexes[i].Unlock()
  374. }
  375. subscribersTimeMutexes[i].Unlock()
  376. },
  377. })
  378. }
  379. // 14
  380. if topic == masterConfig.TopicOfHeartbeatInfo && len(masterConfig.RuleOfHeartbeatInfo) > 0 {
  381. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  382. Node: commonConfig.RosNode,
  383. Topic: topic,
  384. Callback: func(data *pjisuv_msgs.HeartBeatInfo) {
  385. subscribersTimeMutexes[i].Lock()
  386. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  387. subscribersMutexes[i].Lock()
  388. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  389. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  390. var faultLabel string
  391. for _, f := range masterConfig.RuleOfHeartbeatInfo {
  392. faultLabel = f(data)
  393. if faultLabel != "" {
  394. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  395. subscribersTimes[i] = time.Now()
  396. break
  397. }
  398. }
  399. subscribersMutexes[i].Unlock()
  400. }
  401. subscribersTimeMutexes[i].Unlock()
  402. },
  403. })
  404. }
  405. // 15
  406. if topic == masterConfig.TopicOfLidarPretreatmentCost && len(masterConfig.RuleOfLidarPretreatmentCost) > 0 {
  407. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  408. Node: commonConfig.RosNode,
  409. Topic: topic,
  410. Callback: func(data *geometry_msgs.Vector3Stamped) {
  411. subscribersTimeMutexes[i].Lock()
  412. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  413. subscribersMutexes[i].Lock()
  414. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  415. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  416. var faultLabel string
  417. for _, f := range masterConfig.RuleOfLidarPretreatmentCost {
  418. faultLabel = f(data)
  419. if faultLabel != "" {
  420. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  421. subscribersTimes[i] = time.Now()
  422. break
  423. }
  424. }
  425. subscribersMutexes[i].Unlock()
  426. }
  427. subscribersTimeMutexes[i].Unlock()
  428. },
  429. })
  430. }
  431. // 16
  432. if topic == masterConfig.TopicOfLidarPretreatmentOdometry && len(masterConfig.RuleOfLidarPretreatmentOdometry) > 0 {
  433. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  434. Node: commonConfig.RosNode,
  435. Topic: topic,
  436. Callback: func(data *nav_msgs.Odometry) {
  437. subscribersTimeMutexes[i].Lock()
  438. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  439. subscribersMutexes[i].Lock()
  440. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  441. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  442. var faultLabel string
  443. for _, f := range masterConfig.RuleOfLidarPretreatmentOdometry {
  444. faultLabel = f(data)
  445. if faultLabel != "" {
  446. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  447. subscribersTimes[i] = time.Now()
  448. break
  449. }
  450. }
  451. subscribersMutexes[i].Unlock()
  452. }
  453. subscribersTimeMutexes[i].Unlock()
  454. },
  455. })
  456. }
  457. // 17
  458. if topic == masterConfig.TopicOfLidarRoi && len(masterConfig.RuleOfLidarRoi) > 0 {
  459. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  460. Node: commonConfig.RosNode,
  461. Topic: topic,
  462. Callback: func(data *geometry_msgs.PolygonStamped) {
  463. subscribersTimeMutexes[i].Lock()
  464. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  465. subscribersMutexes[i].Lock()
  466. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  467. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  468. var faultLabel string
  469. for _, f := range masterConfig.RuleOfLidarRoi {
  470. faultLabel = f(data)
  471. if faultLabel != "" {
  472. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  473. subscribersTimes[i] = time.Now()
  474. break
  475. }
  476. }
  477. subscribersMutexes[i].Unlock()
  478. }
  479. subscribersTimeMutexes[i].Unlock()
  480. },
  481. })
  482. }
  483. // 18
  484. if topic == masterConfig.TopicOfLine1 && len(masterConfig.RuleOfLine1) > 0 {
  485. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  486. Node: commonConfig.RosNode,
  487. Topic: topic,
  488. Callback: func(data *nav_msgs.Path) {
  489. subscribersTimeMutexes[i].Lock()
  490. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  491. subscribersMutexes[i].Lock()
  492. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  493. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  494. var faultLabel string
  495. for _, f := range masterConfig.RuleOfLine1 {
  496. faultLabel = f(data)
  497. if faultLabel != "" {
  498. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  499. subscribersTimes[i] = time.Now()
  500. break
  501. }
  502. }
  503. subscribersMutexes[i].Unlock()
  504. }
  505. subscribersTimeMutexes[i].Unlock()
  506. },
  507. })
  508. }
  509. // 19
  510. if topic == masterConfig.TopicOfLine2 && len(masterConfig.RuleOfLine2) > 0 {
  511. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  512. Node: commonConfig.RosNode,
  513. Topic: topic,
  514. Callback: func(data *nav_msgs.Path) {
  515. subscribersTimeMutexes[i].Lock()
  516. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  517. subscribersMutexes[i].Lock()
  518. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  519. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  520. var faultLabel string
  521. for _, f := range masterConfig.RuleOfLine2 {
  522. faultLabel = f(data)
  523. if faultLabel != "" {
  524. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  525. subscribersTimes[i] = time.Now()
  526. break
  527. }
  528. }
  529. subscribersMutexes[i].Unlock()
  530. }
  531. subscribersTimeMutexes[i].Unlock()
  532. },
  533. })
  534. }
  535. // 20
  536. if topic == masterConfig.TopicOfMapPolygon && len(masterConfig.RuleOfMapPolygon) > 0 {
  537. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  538. Node: commonConfig.RosNode,
  539. Topic: topic,
  540. Callback: func(data *pjisuv_msgs.PolygonStamped) {
  541. subscribersTimeMutexes[i].Lock()
  542. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  543. subscribersMutexes[i].Lock()
  544. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  545. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  546. var faultLabel string
  547. for _, f := range masterConfig.RuleOfMapPolygon {
  548. faultLabel = f(data)
  549. if faultLabel != "" {
  550. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  551. subscribersTimes[i] = time.Now()
  552. break
  553. }
  554. }
  555. subscribersMutexes[i].Unlock()
  556. }
  557. subscribersTimeMutexes[i].Unlock()
  558. },
  559. })
  560. }
  561. // 21
  562. if topic == masterConfig.TopicOfObstacleDisplay && len(masterConfig.RuleOfObstacleDisplay) > 0 {
  563. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  564. Node: commonConfig.RosNode,
  565. Topic: topic,
  566. Callback: func(data *visualization_msgs.MarkerArray) {
  567. subscribersTimeMutexes[i].Lock()
  568. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  569. subscribersMutexes[i].Lock()
  570. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  571. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  572. var faultLabel string
  573. for _, f := range masterConfig.RuleOfObstacleDisplay {
  574. faultLabel = f(data)
  575. if faultLabel != "" {
  576. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  577. subscribersTimes[i] = time.Now()
  578. break
  579. }
  580. }
  581. subscribersMutexes[i].Unlock()
  582. }
  583. subscribersTimeMutexes[i].Unlock()
  584. },
  585. })
  586. }
  587. // 22
  588. if topic == masterConfig.TopicOfPjControlPub && len(masterConfig.RuleOfPjControlPub) > 0 {
  589. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  590. Node: commonConfig.RosNode,
  591. Topic: topic,
  592. Callback: func(data *pjisuv_msgs.CommonVehicleCmd) {
  593. subscribersTimeMutexes[i].Lock()
  594. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  595. subscribersMutexes[i].Lock()
  596. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  597. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  598. var faultLabel string
  599. for _, f := range masterConfig.RuleOfPjControlPub {
  600. faultLabel = f(data)
  601. if faultLabel != "" {
  602. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  603. subscribersTimes[i] = time.Now()
  604. break
  605. }
  606. }
  607. subscribersMutexes[i].Unlock()
  608. }
  609. subscribersTimeMutexes[i].Unlock()
  610. },
  611. })
  612. }
  613. // 23
  614. if topic == masterConfig.TopicOfPointsCluster && len(masterConfig.RuleOfPointsCluster) > 0 {
  615. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  616. Node: commonConfig.RosNode,
  617. Topic: topic,
  618. Callback: func(data *sensor_msgs.PointCloud2) {
  619. subscribersTimeMutexes[i].Lock()
  620. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  621. subscribersMutexes[i].Lock()
  622. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  623. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  624. var faultLabel string
  625. for _, f := range masterConfig.RuleOfPointsCluster {
  626. faultLabel = f(data)
  627. if faultLabel != "" {
  628. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  629. subscribersTimes[i] = time.Now()
  630. break
  631. }
  632. }
  633. subscribersMutexes[i].Unlock()
  634. }
  635. subscribersTimeMutexes[i].Unlock()
  636. },
  637. })
  638. }
  639. // 24
  640. if topic == masterConfig.TopicOfPointsConcat && len(masterConfig.RuleOfPointsConcat) > 0 {
  641. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  642. Node: commonConfig.RosNode,
  643. Topic: topic,
  644. Callback: func(data *sensor_msgs.PointCloud2) {
  645. subscribersTimeMutexes[i].Lock()
  646. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  647. subscribersMutexes[i].Lock()
  648. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  649. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  650. var faultLabel string
  651. for _, f := range masterConfig.RuleOfPointsConcat {
  652. faultLabel = f(data)
  653. if faultLabel != "" {
  654. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  655. subscribersTimes[i] = time.Now()
  656. break
  657. }
  658. }
  659. subscribersMutexes[i].Unlock()
  660. }
  661. subscribersTimeMutexes[i].Unlock()
  662. },
  663. })
  664. }
  665. // 25
  666. if topic == masterConfig.TopicOfReferenceDisplay && len(masterConfig.RuleOfReferenceDisplay) > 0 {
  667. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  668. Node: commonConfig.RosNode,
  669. Topic: topic,
  670. Callback: func(data *nav_msgs.Path) {
  671. subscribersTimeMutexes[i].Lock()
  672. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  673. subscribersMutexes[i].Lock()
  674. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  675. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  676. var faultLabel string
  677. for _, f := range masterConfig.RuleOfReferenceDisplay {
  678. faultLabel = f(data)
  679. if faultLabel != "" {
  680. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  681. subscribersTimes[i] = time.Now()
  682. break
  683. }
  684. }
  685. subscribersMutexes[i].Unlock()
  686. }
  687. subscribersTimeMutexes[i].Unlock()
  688. },
  689. })
  690. }
  691. // 26
  692. if topic == masterConfig.TopicOfReferenceTrajectory && len(masterConfig.RuleOfReferenceTrajectory) > 0 {
  693. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  694. Node: commonConfig.RosNode,
  695. Topic: topic,
  696. Callback: func(data *pjisuv_msgs.Trajectory) {
  697. subscribersTimeMutexes[i].Lock()
  698. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  699. subscribersMutexes[i].Lock()
  700. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  701. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  702. var faultLabel string
  703. for _, f := range masterConfig.RuleOfReferenceTrajectory {
  704. faultLabel = f(data)
  705. if faultLabel != "" {
  706. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  707. subscribersTimes[i] = time.Now()
  708. break
  709. }
  710. }
  711. subscribersMutexes[i].Unlock()
  712. }
  713. subscribersTimeMutexes[i].Unlock()
  714. },
  715. })
  716. }
  717. // 27
  718. if topic == masterConfig.TopicOfRoiPoints && len(masterConfig.RuleOfRoiPoints) > 0 {
  719. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  720. Node: commonConfig.RosNode,
  721. Topic: topic,
  722. Callback: func(data *sensor_msgs.PointCloud2) {
  723. subscribersTimeMutexes[i].Lock()
  724. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  725. subscribersMutexes[i].Lock()
  726. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  727. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  728. var faultLabel string
  729. for _, f := range masterConfig.RuleOfRoiPoints {
  730. faultLabel = f(data)
  731. if faultLabel != "" {
  732. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  733. subscribersTimes[i] = time.Now()
  734. break
  735. }
  736. }
  737. subscribersMutexes[i].Unlock()
  738. }
  739. subscribersTimeMutexes[i].Unlock()
  740. },
  741. })
  742. }
  743. // 28
  744. if topic == masterConfig.TopicOfRoiPolygon && len(masterConfig.RuleOfRoiPolygon) > 0 {
  745. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  746. Node: commonConfig.RosNode,
  747. Topic: topic,
  748. Callback: func(data *nav_msgs.Path) {
  749. subscribersTimeMutexes[i].Lock()
  750. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  751. subscribersMutexes[i].Lock()
  752. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  753. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  754. var faultLabel string
  755. for _, f := range masterConfig.RuleOfRoiPolygon {
  756. faultLabel = f(data)
  757. if faultLabel != "" {
  758. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  759. subscribersTimes[i] = time.Now()
  760. break
  761. }
  762. }
  763. subscribersMutexes[i].Unlock()
  764. }
  765. subscribersTimeMutexes[i].Unlock()
  766. },
  767. })
  768. }
  769. // 29
  770. if topic == masterConfig.TopicOfTf && len(masterConfig.RuleOfTf) > 0 {
  771. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  772. Node: commonConfig.RosNode,
  773. Topic: topic,
  774. Callback: func(data *tf2_msgs.TFMessage) {
  775. subscribersTimeMutexes[i].Lock()
  776. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  777. subscribersMutexes[i].Lock()
  778. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  779. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  780. var faultLabel string
  781. for _, f := range masterConfig.RuleOfTf {
  782. faultLabel = f(data)
  783. if faultLabel != "" {
  784. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  785. subscribersTimes[i] = time.Now()
  786. break
  787. }
  788. }
  789. subscribersMutexes[i].Unlock()
  790. }
  791. subscribersTimeMutexes[i].Unlock()
  792. },
  793. })
  794. }
  795. // 30
  796. if topic == masterConfig.TopicOfTpperception && len(masterConfig.RuleOfTpperception) > 0 {
  797. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  798. Node: commonConfig.RosNode,
  799. Topic: topic,
  800. Callback: func(data *pjisuv_msgs.PerceptionObjects) {
  801. subscribersTimeMutexes[i].Lock()
  802. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  803. subscribersMutexes[i].Lock()
  804. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  805. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  806. var faultLabel string
  807. for _, f := range masterConfig.RuleOfTpperception {
  808. faultLabel = f(data, velocityX, velocityY, yaw)
  809. if faultLabel != "" {
  810. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  811. break
  812. }
  813. }
  814. subscribersMutexes[i].Unlock()
  815. }
  816. subscribersTimeMutexes[i].Unlock()
  817. },
  818. })
  819. }
  820. // 31
  821. if topic == masterConfig.TopicOfTpperceptionVis && len(masterConfig.RuleOfTpperceptionVis) > 0 {
  822. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  823. Node: commonConfig.RosNode,
  824. Topic: topic,
  825. Callback: func(data *visualization_msgs.MarkerArray) {
  826. subscribersTimeMutexes[i].Lock()
  827. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  828. subscribersMutexes[i].Lock()
  829. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  830. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  831. var faultLabel string
  832. for _, f := range masterConfig.RuleOfTpperceptionVis {
  833. faultLabel = f(data)
  834. if faultLabel != "" {
  835. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  836. subscribersTimes[i] = time.Now()
  837. break
  838. }
  839. }
  840. subscribersMutexes[i].Unlock()
  841. }
  842. subscribersTimeMutexes[i].Unlock()
  843. },
  844. })
  845. }
  846. // 32
  847. if topic == masterConfig.TopicOfTprouteplan && len(masterConfig.RuleOfTprouteplan) > 0 {
  848. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  849. Node: commonConfig.RosNode,
  850. Topic: topic,
  851. Callback: func(data *pjisuv_msgs.RoutePlan) {
  852. subscribersTimeMutexes[i].Lock()
  853. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  854. subscribersMutexes[i].Lock()
  855. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  856. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  857. var faultLabel string
  858. for _, f := range masterConfig.RuleOfTprouteplan {
  859. faultLabel = f(data)
  860. if faultLabel != "" {
  861. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  862. subscribersTimes[i] = time.Now()
  863. break
  864. }
  865. }
  866. subscribersMutexes[i].Unlock()
  867. }
  868. subscribersTimeMutexes[i].Unlock()
  869. },
  870. })
  871. }
  872. // 33
  873. if topic == masterConfig.TopicOfTrajectoryDisplay && len(masterConfig.RuleOfTrajectoryDisplay) > 0 {
  874. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  875. Node: commonConfig.RosNode,
  876. Topic: topic,
  877. Callback: func(data *nav_msgs.Path) {
  878. subscribersTimeMutexes[i].Lock()
  879. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  880. subscribersMutexes[i].Lock()
  881. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  882. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  883. var faultLabel string
  884. for _, f := range masterConfig.RuleOfTrajectoryDisplay {
  885. faultLabel = f(data)
  886. if faultLabel != "" {
  887. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  888. subscribersTimes[i] = time.Now()
  889. break
  890. }
  891. }
  892. subscribersMutexes[i].Unlock()
  893. }
  894. subscribersTimeMutexes[i].Unlock()
  895. },
  896. })
  897. }
  898. // 34
  899. if topic == masterConfig.TopicOfUngroundCloudpoints && len(masterConfig.RuleOfUngroundCloudpoints) > 0 {
  900. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  901. Node: commonConfig.RosNode,
  902. Topic: topic,
  903. Callback: func(data *sensor_msgs.PointCloud2) {
  904. subscribersTimeMutexes[i].Lock()
  905. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  906. subscribersMutexes[i].Lock()
  907. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  908. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  909. var faultLabel string
  910. for _, f := range masterConfig.RuleOfUngroundCloudpoints {
  911. faultLabel = f(data)
  912. if faultLabel != "" {
  913. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  914. subscribersTimes[i] = time.Now()
  915. break
  916. }
  917. }
  918. subscribersMutexes[i].Unlock()
  919. }
  920. subscribersTimeMutexes[i].Unlock()
  921. },
  922. })
  923. }
  924. // 35
  925. if topic == masterConfig.TopicOfCameraImage && len(masterConfig.RuleOfCameraImage) > 0 {
  926. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  927. Node: commonConfig.RosNode,
  928. Topic: topic,
  929. Callback: func(data *sensor_msgs.Image) {
  930. subscribersTimeMutexes[i].Lock()
  931. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  932. subscribersMutexes[i].Lock()
  933. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  934. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  935. var faultLabel string
  936. for _, f := range masterConfig.RuleOfCameraImage {
  937. faultLabel = f(data)
  938. if faultLabel != "" {
  939. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  940. subscribersTimes[i] = time.Now()
  941. break
  942. }
  943. }
  944. subscribersMutexes[i].Unlock()
  945. }
  946. subscribersTimeMutexes[i].Unlock()
  947. },
  948. })
  949. }
  950. // 36
  951. if topic == masterConfig.TopicOfCameraObstacles && len(masterConfig.RuleOfCameraObstacles) > 0 {
  952. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  953. Node: commonConfig.RosNode,
  954. Topic: topic,
  955. Callback: func(data *pjisuv_msgs.CameraObjectList) {
  956. subscribersTimeMutexes[i].Lock()
  957. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  958. subscribersMutexes[i].Lock()
  959. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  960. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  961. var faultLabel string
  962. for _, f := range masterConfig.RuleOfCameraObstacles {
  963. faultLabel = f(data)
  964. if faultLabel != "" {
  965. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  966. subscribersTimes[i] = time.Now()
  967. break
  968. }
  969. }
  970. subscribersMutexes[i].Unlock()
  971. }
  972. subscribersTimeMutexes[i].Unlock()
  973. },
  974. })
  975. }
  976. // 37
  977. if topic == masterConfig.TopicOfCamRes && len(masterConfig.RuleOfCamRes) > 0 {
  978. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  979. Node: commonConfig.RosNode,
  980. Topic: topic,
  981. Callback: func(data *sensor_msgs.Image) {
  982. subscribersTimeMutexes[i].Lock()
  983. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  984. subscribersMutexes[i].Lock()
  985. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  986. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  987. var faultLabel string
  988. for _, f := range masterConfig.RuleOfCamRes {
  989. faultLabel = f(data)
  990. if faultLabel != "" {
  991. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  992. subscribersTimes[i] = time.Now()
  993. break
  994. }
  995. }
  996. subscribersMutexes[i].Unlock()
  997. }
  998. subscribersTimeMutexes[i].Unlock()
  999. },
  1000. })
  1001. }
  1002. // 38
  1003. if topic == masterConfig.TopicOfCamObjects && len(masterConfig.RuleOfCamObjects) > 0 {
  1004. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  1005. Node: commonConfig.RosNode,
  1006. Topic: topic,
  1007. Callback: func(data *pjisuv_msgs.CameraObjectList) {
  1008. subscribersTimeMutexes[i].Lock()
  1009. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  1010. subscribersMutexes[i].Lock()
  1011. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  1012. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  1013. var faultLabel string
  1014. for _, f := range masterConfig.RuleOfCamObjects {
  1015. faultLabel = f(data)
  1016. if faultLabel != "" {
  1017. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  1018. subscribersTimes[i] = time.Now()
  1019. break
  1020. }
  1021. }
  1022. subscribersMutexes[i].Unlock()
  1023. }
  1024. subscribersTimeMutexes[i].Unlock()
  1025. },
  1026. })
  1027. }
  1028. // 39
  1029. if topic == masterConfig.TopicOfTftrafficlight && len(masterConfig.RuleOfTftrafficlight) > 0 {
  1030. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  1031. Node: commonConfig.RosNode,
  1032. Topic: topic,
  1033. Callback: func(data *pjisuv_msgs.TrafficLightDetection) {
  1034. subscribersTimeMutexes[i].Lock()
  1035. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  1036. subscribersMutexes[i].Lock()
  1037. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  1038. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  1039. var faultLabel string
  1040. for _, f := range masterConfig.RuleOfTftrafficlight {
  1041. faultLabel = f(data)
  1042. if faultLabel != "" {
  1043. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  1044. subscribersTimes[i] = time.Now()
  1045. break
  1046. }
  1047. }
  1048. subscribersMutexes[i].Unlock()
  1049. }
  1050. subscribersTimeMutexes[i].Unlock()
  1051. },
  1052. })
  1053. }
  1054. // 40
  1055. if topic == masterConfig.TopicOfStationStatus && len(masterConfig.RuleOfStationStatus) > 0 {
  1056. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  1057. Node: commonConfig.RosNode,
  1058. Topic: topic,
  1059. Callback: func(data *std_msgs.Bool) {
  1060. subscribersTimeMutexes[i].Lock()
  1061. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  1062. subscribersMutexes[i].Lock()
  1063. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  1064. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  1065. var faultLabel string
  1066. for _, f := range masterConfig.RuleOfStationStatus {
  1067. faultLabel = f(data)
  1068. if faultLabel != "" {
  1069. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  1070. subscribersTimes[i] = time.Now()
  1071. break
  1072. }
  1073. }
  1074. subscribersMutexes[i].Unlock()
  1075. }
  1076. subscribersTimeMutexes[i].Unlock()
  1077. },
  1078. })
  1079. }
  1080. // 41
  1081. if topic == masterConfig.TopicOfDestinationPose && len(masterConfig.RuleOfDestinationPose) > 0 {
  1082. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  1083. Node: commonConfig.RosNode,
  1084. Topic: topic,
  1085. Callback: func(data *visualization_msgs.MarkerArray) {
  1086. subscribersTimeMutexes[i].Lock()
  1087. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  1088. subscribersMutexes[i].Lock()
  1089. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  1090. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  1091. var faultLabel string
  1092. for _, f := range masterConfig.RuleOfDestinationPose {
  1093. faultLabel = f(data)
  1094. if faultLabel != "" {
  1095. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  1096. subscribersTimes[i] = time.Now()
  1097. break
  1098. }
  1099. }
  1100. subscribersMutexes[i].Unlock()
  1101. }
  1102. subscribersTimeMutexes[i].Unlock()
  1103. },
  1104. })
  1105. }
  1106. // 42
  1107. if topic == masterConfig.TopicOfMapDisplay && len(masterConfig.RuleOfMapDisplay) > 0 {
  1108. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  1109. Node: commonConfig.RosNode,
  1110. Topic: topic,
  1111. Callback: func(data *nav_msgs.Path) {
  1112. subscribersTimeMutexes[i].Lock()
  1113. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  1114. subscribersMutexes[i].Lock()
  1115. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  1116. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  1117. var faultLabel string
  1118. for _, f := range masterConfig.RuleOfMapDisplay {
  1119. faultLabel = f(data)
  1120. if faultLabel != "" {
  1121. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  1122. subscribersTimes[i] = time.Now()
  1123. break
  1124. }
  1125. }
  1126. subscribersMutexes[i].Unlock()
  1127. }
  1128. subscribersTimeMutexes[i].Unlock()
  1129. },
  1130. })
  1131. }
  1132. // 43
  1133. if topic == masterConfig.TopicOfRoutingRviz && len(masterConfig.RuleOfRoutingRviz) > 0 {
  1134. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  1135. Node: commonConfig.RosNode,
  1136. Topic: topic,
  1137. Callback: func(data *nav_msgs.Path) {
  1138. subscribersTimeMutexes[i].Lock()
  1139. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  1140. subscribersMutexes[i].Lock()
  1141. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  1142. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  1143. var faultLabel string
  1144. for _, f := range masterConfig.RuleOfRoutingRviz {
  1145. faultLabel = f(data)
  1146. if faultLabel != "" {
  1147. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  1148. subscribersTimes[i] = time.Now()
  1149. break
  1150. }
  1151. }
  1152. subscribersMutexes[i].Unlock()
  1153. }
  1154. subscribersTimeMutexes[i].Unlock()
  1155. },
  1156. })
  1157. }
  1158. // 44
  1159. if topic == masterConfig.TopicOfDataRead && len(masterConfig.RuleOfDataRead) > 0 {
  1160. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  1161. Node: commonConfig.RosNode,
  1162. Topic: topic,
  1163. Callback: func(data *pjisuv_msgs.Retrieval) {
  1164. subscribersTimeMutexes[i].Lock()
  1165. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  1166. subscribersMutexes[i].Lock()
  1167. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  1168. lastTimeWindow := entity.GetLastTimeWindow() // 获取最后一个时间窗口
  1169. var faultLabel string
  1170. for _, f := range masterConfig.RuleOfDataRead {
  1171. faultLabel = f(data)
  1172. if faultLabel != "" {
  1173. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  1174. subscribersTimes[i] = time.Now()
  1175. break
  1176. }
  1177. }
  1178. subscribersMutexes[i].Unlock()
  1179. }
  1180. subscribersTimeMutexes[i].Unlock()
  1181. },
  1182. })
  1183. }
  1184. if err != nil {
  1185. c_log.GlobalLogger.Info("创建订阅者报错:", err)
  1186. //TODO 如何回传日志
  1187. continue
  1188. }
  1189. }
  1190. select {
  1191. case signal := <-service.ChannelKillWindowProducer:
  1192. if signal == 1 {
  1193. commonConfig.RosNode.Close()
  1194. service.AddKillTimes("3")
  1195. return
  1196. }
  1197. }
  1198. }
  1199. func saveTimeWindow(faultLabel string, faultHappenTime string, lastTimeWindow *entity.TimeWindow) {
  1200. masterTopics, slaveTopics := getTopicsOfNode(faultLabel)
  1201. if lastTimeWindow == nil || util.TimeCustom1GreaterTimeCustom2(faultHappenTime, lastTimeWindow.TimeWindowEnd) {
  1202. // 2-1 如果是不在旧故障窗口内,添加一个新窗口
  1203. newTimeWindow := entity.TimeWindow{
  1204. FaultTime: faultHappenTime,
  1205. TimeWindowBegin: util.TimeCustomChange(faultHappenTime, -commonConfig.PlatformConfig.TaskBeforeTime),
  1206. TimeWindowEnd: util.TimeCustomChange(faultHappenTime, commonConfig.PlatformConfig.TaskAfterTime),
  1207. Length: commonConfig.PlatformConfig.TaskBeforeTime + commonConfig.PlatformConfig.TaskAfterTime + 1,
  1208. Labels: []string{faultLabel},
  1209. MasterTopics: masterTopics,
  1210. SlaveTopics: slaveTopics,
  1211. }
  1212. c_log.GlobalLogger.Infof("不在旧故障窗口内,向生产者队列添加一个新窗口,【Lable】=%v,【FaultTime】=%v,【Length】=%v", newTimeWindow.Labels, newTimeWindow.FaultTime, newTimeWindow.Length)
  1213. entity.AddTimeWindowToTimeWindowProducerQueue(newTimeWindow)
  1214. } else {
  1215. // 2-2 如果在旧故障窗口内
  1216. entity.TimeWindowProducerQueueMutex.RLock()
  1217. defer entity.TimeWindowProducerQueueMutex.RUnlock()
  1218. // 2-2-1 更新故障窗口end时间
  1219. maxEnd := util.TimeCustomChange(lastTimeWindow.TimeWindowBegin, commonConfig.PlatformConfig.TaskMaxTime)
  1220. expectEnd := util.TimeCustomChange(faultHappenTime, commonConfig.PlatformConfig.TaskAfterTime)
  1221. if util.TimeCustom1GreaterTimeCustom2(expectEnd, maxEnd) {
  1222. lastTimeWindow.TimeWindowEnd = maxEnd
  1223. lastTimeWindow.Length = commonConfig.PlatformConfig.TaskMaxTime
  1224. } else {
  1225. if util.TimeCustom1GreaterTimeCustom2(expectEnd, lastTimeWindow.TimeWindowEnd) {
  1226. lastTimeWindow.TimeWindowEnd = expectEnd
  1227. lastTimeWindow.Length = util.CalculateDifferenceOfTimeCustom(lastTimeWindow.TimeWindowBegin, expectEnd)
  1228. }
  1229. }
  1230. // 2-2-2 更新label
  1231. labels := lastTimeWindow.Labels
  1232. lastTimeWindow.Labels = util.AppendIfNotExists(labels, faultLabel)
  1233. // 2-2-3 更新 topic
  1234. sourceMasterTopics := lastTimeWindow.MasterTopics
  1235. lastTimeWindow.MasterTopics = util.MergeSlice(sourceMasterTopics, masterTopics)
  1236. sourceSlaveTopics := lastTimeWindow.SlaveTopics
  1237. lastTimeWindow.SlaveTopics = util.MergeSlice(sourceSlaveTopics, slaveTopics)
  1238. c_log.GlobalLogger.Infof("在旧故障窗口内,更新生产者队列最新的窗口,【Lable】=%v,【FaultTime】=%v,【Length】=%v", lastTimeWindow.Labels, lastTimeWindow.FaultTime, lastTimeWindow.Length)
  1239. }
  1240. }
  1241. func getTopicsOfNode(faultLabel string) (masterTopics []string, slaveTopics []string) {
  1242. // 获取所有需要采集的topic
  1243. var faultCodeTopics []string
  1244. for _, code := range commonConfig.CloudConfig.Triggers {
  1245. if code.Label == faultLabel {
  1246. faultCodeTopics = code.Topics
  1247. }
  1248. }
  1249. // 根据不同节点采集的topic进行分配采集
  1250. for _, acceptTopic := range faultCodeTopics {
  1251. for _, host := range commonConfig.CloudConfig.Hosts {
  1252. for _, topic := range host.Topics {
  1253. if host.Name == commonConfig.CloudConfig.Hosts[0].Name && acceptTopic == topic {
  1254. masterTopics = append(masterTopics, acceptTopic)
  1255. }
  1256. if host.Name == commonConfig.CloudConfig.Hosts[1].Name && acceptTopic == topic {
  1257. slaveTopics = append(slaveTopics, acceptTopic)
  1258. }
  1259. }
  1260. }
  1261. }
  1262. return masterTopics, slaveTopics
  1263. }