main.go 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506
  1. package main
  2. import (
  3. pjibotGuideConfig "cicv-data-closedloop/aarch64/pjibot_guide/master/package/config"
  4. pjisuvConfig "cicv-data-closedloop/aarch64/pjisuv/master/config"
  5. "cicv-data-closedloop/common/util"
  6. "cicv-data-closedloop/kinglong_msgs"
  7. "cicv-data-closedloop/pjibot_guide_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 == "pjibot_guide" {
  29. //1 一致
  30. if topic == pjibotGuideConfig.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 == pjibotGuideConfig.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 == pjibotGuideConfig.TopicOfLocateInfo {
  49. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  50. Node: rosNode,
  51. Topic: topic,
  52. Callback: func(data *pjibot_guide_msgs.LocateInfo) {
  53. fmt.Println("收到话题", topic, "的数据", data)
  54. }})
  55. }
  56. //4 一致
  57. if topic == pjibotGuideConfig.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 == pjibotGuideConfig.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 == pjibotGuideConfig.TopicOfSysInfo {
  76. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  77. Node: rosNode,
  78. Topic: topic,
  79. Callback: func(data *pjibot_guide_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. fmt.Println("当前 poxitionX 为", data.PositionX, ",positionY 为", data.PositionY)
  194. }})
  195. }
  196. //13 一致
  197. // history 消息不一致
  198. if topic == pjisuvConfig.TopicOfCloudClusters {
  199. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  200. Node: rosNode,
  201. Topic: topic,
  202. Callback: func(data *pjisuv_msgs.AutowareCloudClusterArray) {
  203. fmt.Println("收到话题", topic, "的数据", data)
  204. }})
  205. }
  206. //14 一致
  207. if topic == pjisuvConfig.TopicOfHeartbeatInfo {
  208. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  209. Node: rosNode,
  210. Topic: topic,
  211. Callback: func(data *pjisuv_msgs.HeartBeatInfo) {
  212. fmt.Println("收到话题", topic, "的数据", data)
  213. }})
  214. }
  215. //15 一致
  216. if topic == pjisuvConfig.TopicOfLidarPretreatmentCost {
  217. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  218. Node: rosNode,
  219. Topic: topic,
  220. Callback: func(data *geometry_msgs.Vector3Stamped) {
  221. fmt.Println("收到话题", topic, "的数据", data)
  222. }})
  223. }
  224. //16 一致
  225. if topic == pjisuvConfig.TopicOfLidarPretreatmentOdometry {
  226. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  227. Node: rosNode,
  228. Topic: topic,
  229. Callback: func(data *nav_msgs.Odometry) {
  230. fmt.Println("收到话题", topic, "的数据", data)
  231. }})
  232. }
  233. //17 一致
  234. if topic == pjisuvConfig.TopicOfLidarRoi {
  235. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  236. Node: rosNode,
  237. Topic: topic,
  238. Callback: func(data *geometry_msgs.PolygonStamped) {
  239. fmt.Println("收到话题", topic, "的数据", data)
  240. }})
  241. }
  242. //18 一致
  243. if topic == pjisuvConfig.TopicOfLine1 {
  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. //19 一致
  252. if topic == pjisuvConfig.TopicOfLine2 {
  253. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  254. Node: rosNode,
  255. Topic: topic,
  256. Callback: func(data *nav_msgs.Path) {
  257. fmt.Println("收到话题", topic, "的数据", data)
  258. }})
  259. }
  260. //20 一致
  261. if topic == pjisuvConfig.TopicOfMapPolygon {
  262. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  263. Node: rosNode,
  264. Topic: topic,
  265. Callback: func(data *pjisuv_msgs.PolygonStamped) {
  266. fmt.Println("收到话题", topic, "的数据", data)
  267. }})
  268. }
  269. //21 一致
  270. if topic == pjisuvConfig.TopicOfObstacleDisplay {
  271. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  272. Node: rosNode,
  273. Topic: topic,
  274. Callback: func(data *visualization_msgs.MarkerArray) {
  275. fmt.Println("收到话题", topic, "的数据", data)
  276. }})
  277. }
  278. //22 一致
  279. if topic == pjisuvConfig.TopicOfPjControlPub {
  280. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  281. Node: rosNode,
  282. Topic: topic,
  283. Callback: func(data *pjisuv_msgs.CommonVehicleCmd) {
  284. fmt.Println("收到话题", topic, "的数据", data)
  285. }})
  286. }
  287. //23 一致
  288. if topic == pjisuvConfig.TopicOfPointsCluster {
  289. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  290. Node: rosNode,
  291. Topic: topic,
  292. Callback: func(data *sensor_msgs.PointCloud2) {
  293. fmt.Println("收到话题", topic, "的数据", data)
  294. }})
  295. }
  296. //24 一致
  297. if topic == pjisuvConfig.TopicOfPointsConcat {
  298. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  299. Node: rosNode,
  300. Topic: topic,
  301. Callback: func(data *sensor_msgs.PointCloud2) {
  302. fmt.Println("收到话题", topic, "的数据", data)
  303. }})
  304. }
  305. //25 一致
  306. // history 没有数据发出(未开启自动驾驶)
  307. if topic == pjisuvConfig.TopicOfReferenceDisplay {
  308. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  309. Node: rosNode,
  310. Topic: topic,
  311. Callback: func(data *nav_msgs.Path) {
  312. fmt.Println("收到话题", topic, "的数据", data)
  313. }})
  314. }
  315. //26 一致
  316. // history 没有数据发出(未开启自动驾驶)
  317. if topic == pjisuvConfig.TopicOfReferenceTrajectory {
  318. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  319. Node: rosNode,
  320. Topic: topic,
  321. Callback: func(data *pjisuv_msgs.Trajectory) {
  322. fmt.Println("收到话题", topic, "的数据", data)
  323. }})
  324. }
  325. //27 一致
  326. // history 没有数据发出(未开启自动驾驶)
  327. if topic == pjisuvConfig.TopicOfRoiPoints {
  328. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  329. Node: rosNode,
  330. Topic: topic,
  331. Callback: func(data *sensor_msgs.PointCloud2) {
  332. fmt.Println("收到话题", topic, "的数据", data)
  333. }})
  334. }
  335. //28 一致
  336. if topic == pjisuvConfig.TopicOfRoiPolygon {
  337. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  338. Node: rosNode,
  339. Topic: topic,
  340. Callback: func(data *nav_msgs.Path) {
  341. fmt.Println("收到话题", topic, "的数据", data)
  342. }})
  343. }
  344. //29 一致
  345. if topic == pjisuvConfig.TopicOfTf {
  346. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  347. Node: rosNode,
  348. Topic: topic,
  349. Callback: func(data *tf2_msgs.TFMessage) {
  350. fmt.Println("收到话题", topic, "的数据", data)
  351. }})
  352. }
  353. //30 一致
  354. if topic == pjisuvConfig.TopicOfTpperception {
  355. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  356. Node: rosNode,
  357. Topic: topic,
  358. Callback: func(data *pjisuv_msgs.PerceptionObjects) {
  359. fmt.Println("收到话题", topic, "的数据", data)
  360. }})
  361. }
  362. //31 一致
  363. // history 没有数据发出(未开启自动驾驶)
  364. if topic == pjisuvConfig.TopicOfTpperceptionVis {
  365. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  366. Node: rosNode,
  367. Topic: topic,
  368. Callback: func(data *visualization_msgs.MarkerArray) {
  369. fmt.Println("收到话题", topic, "的数据", data)
  370. }})
  371. }
  372. //32 一致
  373. if topic == pjisuvConfig.TopicOfTprouteplan {
  374. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  375. Node: rosNode,
  376. Topic: topic,
  377. Callback: func(data *pjisuv_msgs.RoutePlan) {
  378. fmt.Println("收到话题", topic, "的数据", data)
  379. }})
  380. }
  381. //33 一致
  382. // history 没有数据发出(未开启自动驾驶)
  383. if topic == pjisuvConfig.TopicOfTrajectoryDisplay {
  384. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  385. Node: rosNode,
  386. Topic: topic,
  387. Callback: func(data *nav_msgs.Path) {
  388. fmt.Println("收到话题", topic, "的数据", data)
  389. }})
  390. }
  391. //34 一致
  392. if topic == pjisuvConfig.TopicOfUngroundCloudpoints {
  393. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  394. Node: rosNode,
  395. Topic: topic,
  396. Callback: func(data *sensor_msgs.PointCloud2) {
  397. fmt.Println("收到话题", topic, "的数据", data)
  398. }})
  399. }
  400. //35 一致
  401. if topic == pjisuvConfig.TopicOfCameraImage {
  402. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  403. Node: rosNode,
  404. Topic: topic,
  405. Callback: func(data *sensor_msgs.Image) {
  406. fmt.Println("收到话题", topic, "的数据", data)
  407. }})
  408. }
  409. //36 仿真平台部孙亚伦开发的底盘数据读取程序
  410. if topic == pjisuvConfig.TopicOfDataRead {
  411. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  412. Node: rosNode,
  413. Topic: topic,
  414. Callback: func(data *pjisuv_msgs.Retrieval) {
  415. fmt.Println("收到话题", topic, "的数据", data)
  416. }})
  417. }
  418. //37
  419. if topic == pjisuvConfig.TopicOfPjiGps {
  420. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  421. Node: rosNode,
  422. Topic: topic,
  423. Callback: func(data *pjisuv_msgs.PerceptionLocalization) {
  424. fmt.Println("收到话题", topic, "的数据", data)
  425. }})
  426. }
  427. //37
  428. // 自动驾驶状态 0 人工 1 自动
  429. if topic == pjisuvConfig.TopicOfPjVehicleFdbPub {
  430. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  431. Node: rosNode,
  432. Topic: topic,
  433. Callback: func(data *pjisuv_msgs.VehicleFdb) {
  434. fmt.Println("自动驾驶状态为", data.Automode)
  435. }})
  436. }
  437. //37
  438. if topic == pjisuvConfig.TopicOfFaultInfo {
  439. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  440. Node: rosNode,
  441. Topic: topic,
  442. Callback: func(data *pjisuv_msgs.FaultVec) {
  443. fmt.Println("收到话题", topic, "的数据", data)
  444. }})
  445. }
  446. }
  447. TopicOfNodeFaultInfo := "/nodefault_info"
  448. TopicOfCicvLocation := "/cicv_location"
  449. TopicOfTpperception := "/tpperception"
  450. TopicOfFaultInfo := "/fault_info"
  451. TopicOfDataRead := "/data_read"
  452. if eType == "kinglong" {
  453. if topic == TopicOfNodeFaultInfo {
  454. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  455. Node: rosNode,
  456. Topic: TopicOfNodeFaultInfo,
  457. Callback: func(data *kinglong_msgs.FaultInfo) {
  458. fmt.Println("收到话题", topic, "的数据", data)
  459. }})
  460. }
  461. if topic == TopicOfCicvLocation {
  462. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  463. Node: rosNode,
  464. Topic: TopicOfCicvLocation,
  465. Callback: func(data *kinglong_msgs.PerceptionLocalization) {
  466. fmt.Println("收到话题", topic, "的数据", data)
  467. fmt.Println("X坐标为:", data.PositionX)
  468. fmt.Println("Y坐标为:", data.PositionY)
  469. }})
  470. }
  471. if topic == TopicOfTpperception {
  472. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  473. Node: rosNode,
  474. Topic: TopicOfTpperception,
  475. Callback: func(data *kinglong_msgs.PerceptionObjects) {
  476. fmt.Println("收到话题", topic, "的数据", data)
  477. }})
  478. }
  479. if topic == TopicOfFaultInfo {
  480. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  481. Node: rosNode,
  482. Topic: TopicOfFaultInfo,
  483. Callback: func(data *kinglong_msgs.FaultVec) {
  484. fmt.Println("收到话题", topic, "的数据", data)
  485. }})
  486. }
  487. if topic == TopicOfDataRead {
  488. _, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
  489. Node: rosNode,
  490. Topic: TopicOfDataRead,
  491. Callback: func(data *kinglong_msgs.Retrieval) {
  492. fmt.Println("收到话题", topic, "的数据", data)
  493. }})
  494. }
  495. }
  496. fmt.Println("没有收到设备类型【", eType, "】的话题【", topic, "】的数据。")
  497. select {}
  498. }