collect_map.go 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596
  1. package service
  2. import (
  3. "cicv-data-closedloop/aarch64/pji/common/config"
  4. "cicv-data-closedloop/common/config/c_log"
  5. "cicv-data-closedloop/common/util"
  6. "os"
  7. )
  8. func CollectOneMsg() {
  9. collectMap()
  10. collectTfStatic()
  11. collectCostmap()
  12. }
  13. func collectMap() {
  14. // rosbag record -O /root/cicv-data-closedloop/map_data.bag -l 1 /map
  15. ossMapBagObjectKey := config.LocalConfig.OssBasePrefix + config.LocalConfig.EquipmentNo + "/map.bag"
  16. var command []string
  17. command = append(command, "record")
  18. command = append(command, "-O")
  19. command = append(command, config.CloudConfig.MapBagPath)
  20. command = append(command, "-l")
  21. command = append(command, "1")
  22. command = append(command, "/map")
  23. _, s, err := util.ExecuteWithEnvAndDir(config.RosbagEnvs, config.CloudConfig.BagDataDir, config.RosbagPath, command...)
  24. if err != nil {
  25. c_log.GlobalLogger.Error("程序异常退出。采集/map包", command, "出错:", s, "----", err)
  26. os.Exit(-1)
  27. }
  28. c_log.GlobalLogger.Error("采集/map包", command, "完成。")
  29. config.OssMutex.Lock()
  30. err = config.OssBucket.PutObjectFromFile(ossMapBagObjectKey, config.CloudConfig.MapBagPath)
  31. config.OssMutex.Unlock()
  32. if err != nil {
  33. c_log.GlobalLogger.Error("程序异常退出。上传/map包", config.CloudConfig.MapBagPath, "->", ossMapBagObjectKey, "出错:", err)
  34. os.Exit(-1)
  35. }
  36. c_log.GlobalLogger.Error("上传/map包", config.CloudConfig.MapBagPath, "------", ossMapBagObjectKey, "成功。")
  37. }
  38. func collectTfStatic() {
  39. // rosbag record -O /root/cicv-data-closedloop/map_data.bag -l 1 /map
  40. ossMapBagObjectKey := config.LocalConfig.OssBasePrefix + config.LocalConfig.EquipmentNo + "/tfstatic.bag"
  41. var command []string
  42. command = append(command, "record")
  43. command = append(command, "-O")
  44. command = append(command, config.CloudConfig.MapBagPath)
  45. command = append(command, "-l")
  46. command = append(command, "1")
  47. command = append(command, "/tf_static")
  48. _, s, err := util.ExecuteWithEnvAndDir(config.RosbagEnvs, config.CloudConfig.BagDataDir, config.RosbagPath, command...)
  49. if err != nil {
  50. c_log.GlobalLogger.Error("程序异常退出。采集/tf_static包", command, "出错:", s, "----", err)
  51. os.Exit(-1)
  52. }
  53. c_log.GlobalLogger.Error("采集/tf_static包", command, "完成。")
  54. config.OssMutex.Lock()
  55. err = config.OssBucket.PutObjectFromFile(ossMapBagObjectKey, config.CloudConfig.MapBagPath)
  56. config.OssMutex.Unlock()
  57. if err != nil {
  58. c_log.GlobalLogger.Error("程序异常退出。上传/tf_static包", config.CloudConfig.MapBagPath, "->", ossMapBagObjectKey, "出错:", err)
  59. os.Exit(-1)
  60. }
  61. c_log.GlobalLogger.Error("上传/tf_static包", config.CloudConfig.MapBagPath, "------", ossMapBagObjectKey, "成功。")
  62. }
  63. func collectCostmap() {
  64. // rosbag record -O /root/cicv-data-closedloop/map_data.bag -l 1 /map
  65. ossMapBagObjectKey := config.LocalConfig.OssBasePrefix + config.LocalConfig.EquipmentNo + "/costmap.bag"
  66. var command []string
  67. command = append(command, "record")
  68. command = append(command, "-O")
  69. command = append(command, config.CloudConfig.MapBagPath)
  70. command = append(command, "-l")
  71. command = append(command, "1")
  72. command = append(command, "/move_base/global_costmap/costmap")
  73. _, s, err := util.ExecuteWithEnvAndDir(config.RosbagEnvs, config.CloudConfig.BagDataDir, config.RosbagPath, command...)
  74. if err != nil {
  75. c_log.GlobalLogger.Error("程序异常退出。采集/move_base/global_costmap/costmap包", command, "出错:", s, "----", err)
  76. os.Exit(-1)
  77. }
  78. c_log.GlobalLogger.Error("采集/move_base/global_costmap/costmap包", command, "完成。")
  79. config.OssMutex.Lock()
  80. err = config.OssBucket.PutObjectFromFile(ossMapBagObjectKey, config.CloudConfig.MapBagPath)
  81. config.OssMutex.Unlock()
  82. if err != nil {
  83. c_log.GlobalLogger.Error("程序异常退出。上传/move_base/global_costmap/costmap包", config.CloudConfig.MapBagPath, "->", ossMapBagObjectKey, "出错:", err)
  84. os.Exit(-1)
  85. }
  86. c_log.GlobalLogger.Error("上传/move_base/global_costmap/costmap包", config.CloudConfig.MapBagPath, "------", ossMapBagObjectKey, "成功。")
  87. }