main.go 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474
  1. package main
  2. import (
  3. pjiConfig "cicv-data-closedloop/aarch64/pji/master/package/config"
  4. pjisuvConfig "cicv-data-closedloop/aarch64/pjisuv/master/package/config"
  5. "cicv-data-closedloop/common/util"
  6. "cicv-data-closedloop/kinglong_msgs"
  7. "cicv-data-closedloop/pji_msgs"
  8. "cicv-data-closedloop/pjisuv_msgs"
  9. "fmt"
  10. "github.com/bluenviron/goroslib/v2"
  11. "github.com/bluenviron/goroslib/v2/pkg/msgs/diagnostic_msgs"
  12. "github.com/bluenviron/goroslib/v2/pkg/msgs/geometry_msgs"
  13. "github.com/bluenviron/goroslib/v2/pkg/msgs/nav_msgs"
  14. "github.com/bluenviron/goroslib/v2/pkg/msgs/sensor_msgs"
  15. "github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
  16. "github.com/bluenviron/goroslib/v2/pkg/msgs/tf2_msgs"
  17. "github.com/bluenviron/goroslib/v2/pkg/msgs/visualization_msgs"
  18. "os"
  19. )
  20. // main 命令格式 topic-echo.exe pjisuv /cicv_location
  21. func main() {
  22. rosNode, _ := goroslib.NewNode(goroslib.NodeConf{
  23. Name: "cicvDataClosedloopTopicEcho",
  24. MasterAddress: "127.0.0.1:11311",
  25. })
  26. eType := util.ToString(os.Args[1])
  27. topic := util.ToString(os.Args[2])
  28. if eType == "pjisuv" {
  29. //1 一致
  30. if topic == pjiConfig.TopicOfDiagnostics {
  31. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  32. Node: rosNode,
  33. Topic: topic,
  34. Callback: func(data *diagnostic_msgs.DiagnosticArray) {
  35. fmt.Println("收到话题", topic, "的数据", data)
  36. }})
  37. }
  38. //2 一致
  39. if topic == pjiConfig.TopicOfImu {
  40. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  41. Node: rosNode,
  42. Topic: topic,
  43. Callback: func(data *sensor_msgs.Imu) {
  44. fmt.Println("收到话题", topic, "的数据", data)
  45. }})
  46. }
  47. //3 一致
  48. if topic == pjiConfig.TopicOfLocateInfo {
  49. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  50. Node: rosNode,
  51. Topic: topic,
  52. Callback: func(data *pji_msgs.LocateInfo) {
  53. fmt.Println("收到话题", topic, "的数据", data)
  54. }})
  55. }
  56. //4 一致
  57. if topic == pjiConfig.TopicOfObstacleDetection {
  58. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  59. Node: rosNode,
  60. Topic: topic,
  61. Callback: func(data *std_msgs.UInt8) {
  62. fmt.Println("收到话题", topic, "的数据", data)
  63. }})
  64. }
  65. //5 一致
  66. if topic == pjiConfig.TopicOfOdom {
  67. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  68. Node: rosNode,
  69. Topic: topic,
  70. Callback: func(data *nav_msgs.Odometry) {
  71. fmt.Println("收到话题", topic, "的数据", data)
  72. }})
  73. }
  74. //6 一致
  75. if topic == pjiConfig.TopicOfSysInfo {
  76. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  77. Node: rosNode,
  78. Topic: topic,
  79. Callback: func(data *pji_msgs.SysInfo) {
  80. fmt.Println("收到话题", topic, "的数据", data)
  81. }})
  82. }
  83. }
  84. if eType == "pjisuv" {
  85. //1 一致
  86. if topic == pjisuvConfig.TopicOfAmrPose {
  87. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  88. Node: rosNode,
  89. Topic: topic,
  90. Callback: func(data *visualization_msgs.MarkerArray) {
  91. fmt.Println("收到话题", topic, "的数据", data)
  92. }})
  93. }
  94. //2 一致
  95. if topic == pjisuvConfig.TopicOfBoundingBoxesFast {
  96. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  97. Node: rosNode,
  98. Topic: topic,
  99. Callback: func(data *pjisuv_msgs.BoundingBoxArray) {
  100. fmt.Println("收到话题", topic, "的数据", data)
  101. }})
  102. }
  103. //3 一致
  104. if topic == pjisuvConfig.TopicOfCameraFault {
  105. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  106. Node: rosNode,
  107. Topic: topic,
  108. Callback: func(data *pjisuv_msgs.FaultVec) {
  109. fmt.Println("收到话题", topic, "的数据", data)
  110. }})
  111. }
  112. //4 一致
  113. // history 消息不一致
  114. if topic == pjisuvConfig.TopicOfCanData {
  115. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  116. Node: rosNode,
  117. Topic: topic,
  118. Callback: func(data *pjisuv_msgs.Frame) {
  119. fmt.Println("收到话题", topic, "的数据", data)
  120. }})
  121. }
  122. //5 一致
  123. if topic == pjisuvConfig.TopicOfCh128x1LslidarPointCloud {
  124. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  125. Node: rosNode,
  126. Topic: topic,
  127. Callback: func(data *sensor_msgs.PointCloud2) {
  128. fmt.Println("收到话题", topic, "的数据", data)
  129. }})
  130. }
  131. //6 一致
  132. if topic == pjisuvConfig.TopicOfCh64wLLslidarPointCloud {
  133. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  134. Node: rosNode,
  135. Topic: topic,
  136. Callback: func(data *sensor_msgs.PointCloud2) {
  137. fmt.Println("收到话题", topic, "的数据", data)
  138. }})
  139. }
  140. //7 一致
  141. if topic == pjisuvConfig.TopicOfCh64wLScan {
  142. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  143. Node: rosNode,
  144. Topic: topic,
  145. Callback: func(data *sensor_msgs.LaserScan) {
  146. fmt.Println("收到话题", topic, "的数据", data)
  147. }})
  148. }
  149. //8 一致
  150. if topic == pjisuvConfig.TopicOfCh64wRLslidarPointCloud {
  151. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  152. Node: rosNode,
  153. Topic: topic,
  154. Callback: func(data *sensor_msgs.PointCloud2) {
  155. fmt.Println("收到话题", topic, "的数据", data)
  156. }})
  157. }
  158. //9 一致
  159. if topic == pjisuvConfig.TopicOfCh64wRScan {
  160. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  161. Node: rosNode,
  162. Topic: topic,
  163. Callback: func(data *sensor_msgs.LaserScan) {
  164. fmt.Println("收到话题", topic, "的数据", data)
  165. }})
  166. }
  167. //10 一致
  168. if topic == pjisuvConfig.TopicOfCicvLidarclusterMovingObjects {
  169. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  170. Node: rosNode,
  171. Topic: topic,
  172. Callback: func(data *pjisuv_msgs.PerceptionCicvMovingObjects) {
  173. fmt.Println("收到话题", topic, "的数据", data)
  174. }})
  175. }
  176. //11 一致
  177. // history 没有数据发出(未开启自动驾驶)
  178. if topic == pjisuvConfig.TopicOfCicvAmrTrajectory {
  179. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  180. Node: rosNode,
  181. Topic: topic,
  182. Callback: func(data *pjisuv_msgs.Trajectory) {
  183. fmt.Println("收到话题", topic, "的数据", data)
  184. }})
  185. }
  186. //12 一致
  187. if topic == pjisuvConfig.TopicOfCicvLocation {
  188. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  189. Node: rosNode,
  190. Topic: topic,
  191. Callback: func(data *pjisuv_msgs.PerceptionLocalization) {
  192. fmt.Println("收到话题", topic, "的数据", data)
  193. }})
  194. }
  195. //13 一致
  196. // history 消息不一致
  197. if topic == pjisuvConfig.TopicOfCloudClusters {
  198. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  199. Node: rosNode,
  200. Topic: topic,
  201. Callback: func(data *pjisuv_msgs.AutowareCloudClusterArray) {
  202. fmt.Println("收到话题", topic, "的数据", data)
  203. }})
  204. }
  205. //14 一致
  206. if topic == pjisuvConfig.TopicOfHeartbeatInfo {
  207. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  208. Node: rosNode,
  209. Topic: topic,
  210. Callback: func(data *pjisuv_msgs.HeartBeatInfo) {
  211. fmt.Println("收到话题", topic, "的数据", data)
  212. }})
  213. }
  214. //15 一致
  215. if topic == pjisuvConfig.TopicOfLidarPretreatmentCost {
  216. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  217. Node: rosNode,
  218. Topic: topic,
  219. Callback: func(data *geometry_msgs.Vector3Stamped) {
  220. fmt.Println("收到话题", topic, "的数据", data)
  221. }})
  222. }
  223. //16 一致
  224. if topic == pjisuvConfig.TopicOfLidarPretreatmentOdometry {
  225. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  226. Node: rosNode,
  227. Topic: topic,
  228. Callback: func(data *nav_msgs.Odometry) {
  229. fmt.Println("收到话题", topic, "的数据", data)
  230. }})
  231. }
  232. //17 一致
  233. if topic == pjisuvConfig.TopicOfLidarRoi {
  234. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  235. Node: rosNode,
  236. Topic: topic,
  237. Callback: func(data *geometry_msgs.PolygonStamped) {
  238. fmt.Println("收到话题", topic, "的数据", data)
  239. }})
  240. }
  241. //18 一致
  242. if topic == pjisuvConfig.TopicOfLine1 {
  243. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  244. Node: rosNode,
  245. Topic: topic,
  246. Callback: func(data *nav_msgs.Path) {
  247. fmt.Println("收到话题", topic, "的数据", data)
  248. }})
  249. }
  250. //19 一致
  251. if topic == pjisuvConfig.TopicOfLine2 {
  252. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  253. Node: rosNode,
  254. Topic: topic,
  255. Callback: func(data *nav_msgs.Path) {
  256. fmt.Println("收到话题", topic, "的数据", data)
  257. }})
  258. }
  259. //20 一致
  260. if topic == pjisuvConfig.TopicOfMapPolygon {
  261. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  262. Node: rosNode,
  263. Topic: topic,
  264. Callback: func(data *pjisuv_msgs.PolygonStamped) {
  265. fmt.Println("收到话题", topic, "的数据", data)
  266. }})
  267. }
  268. //21 一致
  269. if topic == pjisuvConfig.TopicOfObstacleDisplay {
  270. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  271. Node: rosNode,
  272. Topic: topic,
  273. Callback: func(data *visualization_msgs.MarkerArray) {
  274. fmt.Println("收到话题", topic, "的数据", data)
  275. }})
  276. }
  277. //22 一致
  278. if topic == pjisuvConfig.TopicOfPjControlPub {
  279. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  280. Node: rosNode,
  281. Topic: topic,
  282. Callback: func(data *pjisuv_msgs.CommonVehicleCmd) {
  283. fmt.Println("收到话题", topic, "的数据", data)
  284. }})
  285. }
  286. //23 一致
  287. if topic == pjisuvConfig.TopicOfPointsCluster {
  288. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  289. Node: rosNode,
  290. Topic: topic,
  291. Callback: func(data *sensor_msgs.PointCloud2) {
  292. fmt.Println("收到话题", topic, "的数据", data)
  293. }})
  294. }
  295. //24 一致
  296. if topic == pjisuvConfig.TopicOfPointsConcat {
  297. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  298. Node: rosNode,
  299. Topic: topic,
  300. Callback: func(data *sensor_msgs.PointCloud2) {
  301. fmt.Println("收到话题", topic, "的数据", data)
  302. }})
  303. }
  304. //25 一致
  305. // history 没有数据发出(未开启自动驾驶)
  306. if topic == pjisuvConfig.TopicOfReferenceDisplay {
  307. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  308. Node: rosNode,
  309. Topic: topic,
  310. Callback: func(data *nav_msgs.Path) {
  311. fmt.Println("收到话题", topic, "的数据", data)
  312. }})
  313. }
  314. //26 一致
  315. // history 没有数据发出(未开启自动驾驶)
  316. if topic == pjisuvConfig.TopicOfReferenceTrajectory {
  317. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  318. Node: rosNode,
  319. Topic: topic,
  320. Callback: func(data *pjisuv_msgs.Trajectory) {
  321. fmt.Println("收到话题", topic, "的数据", data)
  322. }})
  323. }
  324. //27 一致
  325. // history 没有数据发出(未开启自动驾驶)
  326. if topic == pjisuvConfig.TopicOfRoiPoints {
  327. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  328. Node: rosNode,
  329. Topic: topic,
  330. Callback: func(data *sensor_msgs.PointCloud2) {
  331. fmt.Println("收到话题", topic, "的数据", data)
  332. }})
  333. }
  334. //28 一致
  335. if topic == pjisuvConfig.TopicOfRoiPolygon {
  336. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  337. Node: rosNode,
  338. Topic: topic,
  339. Callback: func(data *nav_msgs.Path) {
  340. fmt.Println("收到话题", topic, "的数据", data)
  341. }})
  342. }
  343. //29 一致
  344. if topic == pjisuvConfig.TopicOfTf {
  345. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  346. Node: rosNode,
  347. Topic: topic,
  348. Callback: func(data *tf2_msgs.TFMessage) {
  349. fmt.Println("收到话题", topic, "的数据", data)
  350. }})
  351. }
  352. //30 一致
  353. if topic == pjisuvConfig.TopicOfTpperception {
  354. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  355. Node: rosNode,
  356. Topic: topic,
  357. Callback: func(data *pjisuv_msgs.PerceptionObjects) {
  358. fmt.Println("收到话题", topic, "的数据", data)
  359. }})
  360. }
  361. //31 一致
  362. // history 没有数据发出(未开启自动驾驶)
  363. if topic == pjisuvConfig.TopicOfTpperceptionVis {
  364. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  365. Node: rosNode,
  366. Topic: topic,
  367. Callback: func(data *visualization_msgs.MarkerArray) {
  368. fmt.Println("收到话题", topic, "的数据", data)
  369. }})
  370. }
  371. //32 一致
  372. if topic == pjisuvConfig.TopicOfTprouteplan {
  373. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  374. Node: rosNode,
  375. Topic: topic,
  376. Callback: func(data *pjisuv_msgs.RoutePlan) {
  377. fmt.Println("收到话题", topic, "的数据", data)
  378. }})
  379. }
  380. //33 一致
  381. // history 没有数据发出(未开启自动驾驶)
  382. if topic == pjisuvConfig.TopicOfTrajectoryDisplay {
  383. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  384. Node: rosNode,
  385. Topic: topic,
  386. Callback: func(data *nav_msgs.Path) {
  387. fmt.Println("收到话题", topic, "的数据", data)
  388. }})
  389. }
  390. //34 一致
  391. if topic == pjisuvConfig.TopicOfUngroundCloudpoints {
  392. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  393. Node: rosNode,
  394. Topic: topic,
  395. Callback: func(data *sensor_msgs.PointCloud2) {
  396. fmt.Println("收到话题", topic, "的数据", data)
  397. }})
  398. }
  399. //35 一致
  400. if topic == pjisuvConfig.TopicOfCameraImage {
  401. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  402. Node: rosNode,
  403. Topic: topic,
  404. Callback: func(data *sensor_msgs.Image) {
  405. fmt.Println("收到话题", topic, "的数据", data)
  406. }})
  407. }
  408. //36 todo 没有数据发出
  409. if topic == pjisuvConfig.TopicOfDataRead {
  410. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  411. Node: rosNode,
  412. Topic: topic,
  413. Callback: func(data *pjisuv_msgs.Retrieval) {
  414. fmt.Println("收到话题", topic, "的数据", data)
  415. }})
  416. }
  417. }
  418. TopicOfNodeFaultInfo := "/nodefault_info"
  419. TopicOfCicvLocation := "/cicv_location"
  420. TopicOfTpperception := "/tpperception"
  421. TopicOfFaultInfo := "/fault_info"
  422. TopicOfDataRead := "/data_read"
  423. if eType == "kinglong" {
  424. if topic == TopicOfNodeFaultInfo {
  425. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  426. Node: rosNode,
  427. Topic: TopicOfNodeFaultInfo,
  428. Callback: func(data *kinglong_msgs.FaultInfo) {
  429. fmt.Println("收到话题", topic, "的数据", data)
  430. }})
  431. }
  432. if topic == TopicOfCicvLocation {
  433. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  434. Node: rosNode,
  435. Topic: TopicOfCicvLocation,
  436. Callback: func(data *kinglong_msgs.PerceptionLocalization) {
  437. fmt.Println("收到话题", topic, "的数据", data)
  438. }})
  439. }
  440. if topic == TopicOfTpperception {
  441. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  442. Node: rosNode,
  443. Topic: TopicOfTpperception,
  444. Callback: func(data *kinglong_msgs.PerceptionObjects) {
  445. fmt.Println("收到话题", topic, "的数据", data)
  446. }})
  447. }
  448. if topic == TopicOfFaultInfo {
  449. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  450. Node: rosNode,
  451. Topic: TopicOfFaultInfo,
  452. Callback: func(data *kinglong_msgs.FaultVec) {
  453. fmt.Println("收到话题", topic, "的数据", data)
  454. }})
  455. }
  456. if topic == TopicOfDataRead {
  457. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  458. Node: rosNode,
  459. Topic: TopicOfDataRead,
  460. Callback: func(data *kinglong_msgs.Retrieval) {
  461. fmt.Println("收到话题", topic, "的数据", data)
  462. }})
  463. }
  464. }
  465. select {}
  466. }