main.go 15 KB

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