produce_window.go 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382
  1. package service
  2. import (
  3. commonConfig "cicv-data-closedloop/aarch64/kinglong/common/config"
  4. "cicv-data-closedloop/aarch64/kinglong/common/service"
  5. masterConfig "cicv-data-closedloop/aarch64/kinglong/master/package/config"
  6. "cicv-data-closedloop/common/config/c_log"
  7. commonEntity "cicv-data-closedloop/common/entity"
  8. "cicv-data-closedloop/common/util"
  9. "cicv-data-closedloop/kinglong_msgs"
  10. "cicv-data-closedloop/kinglong_param"
  11. "github.com/bluenviron/goroslib/v2"
  12. "github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
  13. "math"
  14. "sync"
  15. "time"
  16. )
  17. var (
  18. extendParam kinglong_param.KinglongParam
  19. // /cicv_location
  20. mutexOfCicvLocation sync.RWMutex
  21. // /tpperception
  22. mutexOfTpperception sync.RWMutex
  23. // /pj_control_pub
  24. mutexOfJinlongControlPub sync.RWMutex
  25. // /data_read
  26. mutexOfDataRead sync.RWMutex
  27. )
  28. // PrepareTimeWindowProducerQueue 负责监听所有主题并修改时间窗口
  29. func PrepareTimeWindowProducerQueue() {
  30. c_log.GlobalLogger.Info("订阅者 goroutine,启动。")
  31. var err error
  32. subscribers := make([]*goroslib.Subscriber, len(commonConfig.SubscribeTopics))
  33. subscribersTimes := make([]time.Time, len(commonConfig.SubscribeTopics))
  34. subscribersTimeMutexes := make([]sync.Mutex, len(commonConfig.SubscribeTopics))
  35. subscribersMutexes := make([]sync.Mutex, len(commonConfig.SubscribeTopics))
  36. for i, topic := range commonConfig.SubscribeTopics {
  37. // !!!扩展的定时任务监听,牛逼!!!
  38. if topic == masterConfig.TopicOfCicvExtend {
  39. for {
  40. time.Sleep(time.Duration(3500) * time.Millisecond)
  41. for _, f := range masterConfig.RuleOfCicvExtend {
  42. label := f(extendParam)
  43. if label != "" {
  44. saveTimeWindow(label, util.GetNowTimeCustom(), commonEntity.GetLastTimeWindow())
  45. break
  46. }
  47. }
  48. }
  49. }
  50. c_log.GlobalLogger.Info("创建订阅者订阅话题:" + topic)
  51. if topic == masterConfig.TopicOfCicvLocation && len(masterConfig.RuleOfCicvLocation) > 0 {
  52. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  53. Node: commonConfig.RosNode,
  54. Topic: topic,
  55. Callback: func(data *kinglong_msgs.PerceptionLocalization) {
  56. // 更新共享变量
  57. mutexOfCicvLocation.RLock()
  58. {
  59. extendParam.VelocityYOfCicvLocation = data.VelocityX
  60. extendParam.VelocityYOfCicvLocation = data.VelocityY
  61. extendParam.YawOfCicvLocation = data.Yaw
  62. extendParam.AngularVelocityZOfCicvLocation = data.AngularVelocityZ
  63. }
  64. mutexOfCicvLocation.RUnlock()
  65. subscribersTimeMutexes[i].Lock()
  66. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  67. subscribersMutexes[i].Lock()
  68. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  69. lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
  70. var faultLabel string
  71. for _, f := range masterConfig.RuleOfCicvLocation {
  72. faultLabel = f(data)
  73. if faultLabel != "" {
  74. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  75. break
  76. }
  77. }
  78. subscribersMutexes[i].Unlock()
  79. }
  80. subscribersTimeMutexes[i].Unlock()
  81. },
  82. })
  83. }
  84. if topic == masterConfig.TopicOfTpperception && len(masterConfig.RuleOfTpperception) > 0 {
  85. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  86. Node: commonConfig.RosNode,
  87. Topic: topic,
  88. Callback: func(data *kinglong_msgs.PerceptionObjects) {
  89. // ------- 触发前更新共享变量
  90. mutexOfTpperception.RLock()
  91. {
  92. for _, obj := range data.Objs {
  93. if (obj.Type != 1 && obj.Type != 0) || obj.X <= 5 || math.Abs(float64(obj.Y)) >= 10 {
  94. continue
  95. }
  96. if _, ok := extendParam.ObjDicOfTpperception[obj.Id]; !ok {
  97. extendParam.ObjDicOfTpperception[obj.Id] = []float32{}
  98. }
  99. extendParam.ObjDicOfTpperception[obj.Id] = append(extendParam.ObjDicOfTpperception[obj.Id], obj.Y)
  100. }
  101. }
  102. mutexOfTpperception.RUnlock()
  103. subscribersTimeMutexes[i].Lock()
  104. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  105. subscribersMutexes[i].Lock()
  106. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  107. lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
  108. var faultLabel string
  109. for _, f := range masterConfig.RuleOfTpperception {
  110. faultLabel = f(data, extendParam)
  111. if faultLabel != "" {
  112. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  113. break
  114. }
  115. }
  116. subscribersMutexes[i].Unlock()
  117. }
  118. subscribersTimeMutexes[i].Unlock()
  119. // -------- 触发后更新共享变量
  120. mutexOfTpperception.RLock()
  121. {
  122. for _, obj := range data.Objs {
  123. extendParam.ObjTypeDicOfTpperception[obj.Id] = obj.Type
  124. extendParam.ObjSpeedDicOfTpperception[obj.Id] = math.Pow(math.Pow(float64(obj.Vxabs), 2)+math.Pow(float64(obj.Vyabs), 2), 0.5)
  125. }
  126. }
  127. mutexOfTpperception.RUnlock()
  128. },
  129. })
  130. }
  131. // 5
  132. if topic == masterConfig.TopicOfDataRead {
  133. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  134. Node: commonConfig.RosNode,
  135. Topic: topic,
  136. Callback: func(data *kinglong_msgs.Retrieval) {
  137. // 更新共享变量
  138. mutexOfDataRead.RLock()
  139. {
  140. extendParam.NumCountDataReadOfDataRead++
  141. if extendParam.NumCountDataReadOfDataRead == 10 {
  142. extendParam.EgoSteeringRealOfDataRead = append(extendParam.EgoSteeringRealOfDataRead, data.StrgAngleRealValue)
  143. extendParam.EgoThrottleRealOfDataRead = append(extendParam.EgoThrottleRealOfDataRead, data.VcuAccelPosValue)
  144. extendParam.EgoBrakeRealOfDataRead = append(extendParam.EgoBrakeRealOfDataRead, data.VcuBrkPelPosValue)
  145. extendParam.NumCountDataReadOfDataRead = 0
  146. }
  147. }
  148. mutexOfDataRead.RUnlock()
  149. subscribersTimeMutexes[i].Lock()
  150. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  151. subscribersMutexes[i].Lock()
  152. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  153. lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
  154. var faultLabel string
  155. for _, f := range masterConfig.RuleOfDataRead {
  156. faultLabel = f(data)
  157. if faultLabel != "" {
  158. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  159. subscribersTimes[i] = time.Now()
  160. break
  161. }
  162. }
  163. subscribersMutexes[i].Unlock()
  164. }
  165. subscribersTimeMutexes[i].Unlock()
  166. },
  167. })
  168. }
  169. // 6
  170. if topic == masterConfig.TopicOfJinlongControlPub && len(masterConfig.RuleOfJinlongControlPub) > 0 {
  171. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  172. Node: commonConfig.RosNode,
  173. Topic: topic,
  174. Callback: func(data *kinglong_msgs.JinlongControlCommand) {
  175. // 更新共享变量
  176. mutexOfJinlongControlPub.RLock()
  177. {
  178. extendParam.NumCountJinlongControlCommandOfPjControlPub++
  179. if extendParam.NumCountJinlongControlCommandOfPjControlPub == 10 {
  180. extendParam.EgoSteeringCmdOfJinlongControlPub = append(extendParam.EgoSteeringCmdOfJinlongControlPub, data.ASStrgAngleReq)
  181. extendParam.EgoThrottleCmdOfJinlongControlPub = append(extendParam.EgoThrottleCmdOfJinlongControlPub, data.ASAutoDAccelPosReq)
  182. extendParam.EgoBrakeCmdOfJinlongControlPub = append(extendParam.EgoBrakeCmdOfJinlongControlPub, data.ASAutoDBrkPelPosReq)
  183. extendParam.NumCountJinlongControlCommandOfPjControlPub = 0
  184. }
  185. }
  186. mutexOfJinlongControlPub.RUnlock()
  187. subscribersTimeMutexes[i].Lock()
  188. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  189. subscribersMutexes[i].Lock()
  190. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  191. lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
  192. var faultLabel string
  193. for _, f := range masterConfig.RuleOfJinlongControlPub {
  194. faultLabel = f(data)
  195. if faultLabel != "" {
  196. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  197. break
  198. }
  199. }
  200. subscribersMutexes[i].Unlock()
  201. }
  202. subscribersTimeMutexes[i].Unlock()
  203. },
  204. })
  205. }
  206. // 7
  207. if topic == masterConfig.TopicOfFailureLidar && len(masterConfig.RuleOfFailureLidar) > 0 {
  208. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  209. Node: commonConfig.RosNode,
  210. Topic: topic,
  211. Callback: func(data *std_msgs.Bool) {
  212. subscribersTimeMutexes[i].Lock()
  213. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  214. subscribersMutexes[i].Lock()
  215. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  216. lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
  217. var faultLabel string
  218. for _, f := range masterConfig.RuleOfFailureLidar {
  219. faultLabel = f(data)
  220. if faultLabel != "" {
  221. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  222. break
  223. }
  224. }
  225. subscribersMutexes[i].Unlock()
  226. }
  227. subscribersTimeMutexes[i].Unlock()
  228. },
  229. })
  230. }
  231. // 8
  232. if topic == masterConfig.TopicOfFailureRadar && len(masterConfig.RuleOfFailureRadar) > 0 {
  233. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  234. Node: commonConfig.RosNode,
  235. Topic: topic,
  236. Callback: func(data *std_msgs.Bool) {
  237. subscribersTimeMutexes[i].Lock()
  238. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  239. subscribersMutexes[i].Lock()
  240. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  241. lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
  242. var faultLabel string
  243. for _, f := range masterConfig.RuleOfFailureRadar {
  244. faultLabel = f(data)
  245. if faultLabel != "" {
  246. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  247. break
  248. }
  249. }
  250. subscribersMutexes[i].Unlock()
  251. }
  252. subscribersTimeMutexes[i].Unlock()
  253. },
  254. })
  255. }
  256. // 9
  257. if topic == masterConfig.TopicOfFailureCamera && len(masterConfig.RuleOfFailureLidar) > 0 {
  258. subscribers[i], err = goroslib.NewSubscriber(goroslib.SubscriberConf{
  259. Node: commonConfig.RosNode,
  260. Topic: topic,
  261. Callback: func(data *std_msgs.Bool) {
  262. subscribersTimeMutexes[i].Lock()
  263. if time.Since(subscribersTimes[i]).Seconds() > 1 {
  264. subscribersMutexes[i].Lock()
  265. faultHappenTime := util.GetNowTimeCustom() // 获取当前故障发生时间
  266. lastTimeWindow := commonEntity.GetLastTimeWindow() // 获取最后一个时间窗口
  267. var faultLabel string
  268. for _, f := range masterConfig.RuleOfFailureLidar {
  269. faultLabel = f(data)
  270. if faultLabel != "" {
  271. saveTimeWindow(faultLabel, faultHappenTime, lastTimeWindow)
  272. break
  273. }
  274. }
  275. subscribersMutexes[i].Unlock()
  276. }
  277. subscribersTimeMutexes[i].Unlock()
  278. },
  279. })
  280. }
  281. if err != nil {
  282. c_log.GlobalLogger.Info("创建订阅者报错:", err)
  283. //TODO 如何回传日志
  284. continue
  285. }
  286. }
  287. select {
  288. case signal := <-service.ChannelKillWindowProducer:
  289. if signal == 1 {
  290. commonConfig.RosNode.Close()
  291. service.AddKillTimes("3")
  292. return
  293. }
  294. }
  295. }
  296. func saveTimeWindow(faultLabel string, faultHappenTime string, lastTimeWindow *commonEntity.TimeWindow) {
  297. masterTopics, slaveTopics := getTopicsOfNode(faultLabel)
  298. if lastTimeWindow == nil || util.TimeCustom1GreaterTimeCustom2(faultHappenTime, lastTimeWindow.TimeWindowEnd) {
  299. // 2-1 如果是不在旧故障窗口内,添加一个新窗口
  300. newTimeWindow := commonEntity.TimeWindow{
  301. FaultTime: faultHappenTime,
  302. TimeWindowBegin: util.TimeCustomChange(faultHappenTime, -commonConfig.PlatformConfig.TaskBeforeTime),
  303. TimeWindowEnd: util.TimeCustomChange(faultHappenTime, commonConfig.PlatformConfig.TaskAfterTime),
  304. Length: commonConfig.PlatformConfig.TaskBeforeTime + commonConfig.PlatformConfig.TaskAfterTime + 1,
  305. Labels: []string{faultLabel},
  306. MasterTopics: masterTopics,
  307. SlaveTopics: slaveTopics,
  308. }
  309. c_log.GlobalLogger.Infof("不在旧故障窗口内,向生产者队列添加一个新窗口,【Lable】=%v,【FaultTime】=%v,【Length】=%v", newTimeWindow.Labels, newTimeWindow.FaultTime, newTimeWindow.Length)
  310. commonEntity.AddTimeWindowToTimeWindowProducerQueue(newTimeWindow)
  311. } else {
  312. // 2-2 如果在旧故障窗口内
  313. commonEntity.TimeWindowProducerQueueMutex.RLock()
  314. defer commonEntity.TimeWindowProducerQueueMutex.RUnlock()
  315. // 2-2-1 更新故障窗口end时间
  316. maxEnd := util.TimeCustomChange(lastTimeWindow.TimeWindowBegin, commonConfig.PlatformConfig.TaskMaxTime)
  317. expectEnd := util.TimeCustomChange(faultHappenTime, commonConfig.PlatformConfig.TaskAfterTime)
  318. if util.TimeCustom1GreaterTimeCustom2(expectEnd, maxEnd) {
  319. lastTimeWindow.TimeWindowEnd = maxEnd
  320. lastTimeWindow.Length = commonConfig.PlatformConfig.TaskMaxTime
  321. } else {
  322. if util.TimeCustom1GreaterTimeCustom2(expectEnd, lastTimeWindow.TimeWindowEnd) {
  323. lastTimeWindow.TimeWindowEnd = expectEnd
  324. lastTimeWindow.Length = util.CalculateDifferenceOfTimeCustom(lastTimeWindow.TimeWindowBegin, expectEnd)
  325. }
  326. }
  327. // 2-2-2 更新label
  328. labels := lastTimeWindow.Labels
  329. lastTimeWindow.Labels = util.AppendIfNotExists(labels, faultLabel)
  330. // 2-2-3 更新 topic
  331. sourceMasterTopics := lastTimeWindow.MasterTopics
  332. lastTimeWindow.MasterTopics = util.MergeSlice(sourceMasterTopics, masterTopics)
  333. sourceSlaveTopics := lastTimeWindow.SlaveTopics
  334. lastTimeWindow.SlaveTopics = util.MergeSlice(sourceSlaveTopics, slaveTopics)
  335. c_log.GlobalLogger.Infof("在旧故障窗口内,更新生产者队列最新的窗口,【Lable】=%v,【FaultTime】=%v,【Length】=%v", lastTimeWindow.Labels, lastTimeWindow.FaultTime, lastTimeWindow.Length)
  336. }
  337. }
  338. func getTopicsOfNode(faultLabel string) (masterTopics []string, slaveTopics []string) {
  339. // 获取所有需要采集的topic
  340. var faultCodeTopics []string
  341. for _, code := range commonConfig.CloudConfig.Triggers {
  342. if code.Label == faultLabel {
  343. faultCodeTopics = code.Topics
  344. }
  345. }
  346. // 根据不同节点采集的topic进行分配采集
  347. for _, acceptTopic := range faultCodeTopics {
  348. for _, host := range commonConfig.CloudConfig.Hosts {
  349. for _, topic := range host.Topics {
  350. if host.Name == commonConfig.CloudConfig.Hosts[0].Name && acceptTopic == topic {
  351. masterTopics = append(masterTopics, acceptTopic)
  352. }
  353. if host.Name == commonConfig.CloudConfig.Hosts[1].Name && acceptTopic == topic {
  354. slaveTopics = append(slaveTopics, acceptTopic)
  355. }
  356. }
  357. }
  358. }
  359. return masterTopics, slaveTopics
  360. }