123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596 |
- package service
- import (
- "cicv-data-closedloop/aarch64/pji/common/config"
- "cicv-data-closedloop/common/config/c_log"
- "cicv-data-closedloop/common/util"
- "os"
- )
- func CollectOneMsg() {
- collectMap()
- collectTfStatic()
- collectCostmap()
- }
- func collectMap() {
- // rosbag record -O /root/cicv-data-closedloop/map_data.bag -l 1 /map
- ossMapBagObjectKey := config.LocalConfig.OssBasePrefix + config.LocalConfig.EquipmentNo + "/map.bag"
- var command []string
- command = append(command, "record")
- command = append(command, "-O")
- command = append(command, config.CloudConfig.MapBagPath)
- command = append(command, "-l")
- command = append(command, "1")
- command = append(command, "/map")
- _, s, err := util.ExecuteWithEnvAndDir(config.RosbagEnvs, config.CloudConfig.BagDataDir, config.RosbagPath, command...)
- if err != nil {
- c_log.GlobalLogger.Error("程序异常退出。采集/map包", command, "出错:", s, "----", err)
- os.Exit(-1)
- }
- c_log.GlobalLogger.Error("采集/map包", command, "完成。")
- config.OssMutex.Lock()
- err = config.OssBucket.PutObjectFromFile(ossMapBagObjectKey, config.CloudConfig.MapBagPath)
- config.OssMutex.Unlock()
- if err != nil {
- c_log.GlobalLogger.Error("程序异常退出。上传/map包", config.CloudConfig.MapBagPath, "->", ossMapBagObjectKey, "出错:", err)
- os.Exit(-1)
- }
- c_log.GlobalLogger.Error("上传/map包", config.CloudConfig.MapBagPath, "------", ossMapBagObjectKey, "成功。")
- }
- func collectTfStatic() {
- // rosbag record -O /root/cicv-data-closedloop/map_data.bag -l 1 /map
- ossMapBagObjectKey := config.LocalConfig.OssBasePrefix + config.LocalConfig.EquipmentNo + "/tfstatic.bag"
- var command []string
- command = append(command, "record")
- command = append(command, "-O")
- command = append(command, config.CloudConfig.MapBagPath)
- command = append(command, "-l")
- command = append(command, "1")
- command = append(command, "/tf_static")
- _, s, err := util.ExecuteWithEnvAndDir(config.RosbagEnvs, config.CloudConfig.BagDataDir, config.RosbagPath, command...)
- if err != nil {
- c_log.GlobalLogger.Error("程序异常退出。采集/tf_static包", command, "出错:", s, "----", err)
- os.Exit(-1)
- }
- c_log.GlobalLogger.Error("采集/tf_static包", command, "完成。")
- config.OssMutex.Lock()
- err = config.OssBucket.PutObjectFromFile(ossMapBagObjectKey, config.CloudConfig.MapBagPath)
- config.OssMutex.Unlock()
- if err != nil {
- c_log.GlobalLogger.Error("程序异常退出。上传/tf_static包", config.CloudConfig.MapBagPath, "->", ossMapBagObjectKey, "出错:", err)
- os.Exit(-1)
- }
- c_log.GlobalLogger.Error("上传/tf_static包", config.CloudConfig.MapBagPath, "------", ossMapBagObjectKey, "成功。")
- }
- func collectCostmap() {
- // rosbag record -O /root/cicv-data-closedloop/map_data.bag -l 1 /map
- ossMapBagObjectKey := config.LocalConfig.OssBasePrefix + config.LocalConfig.EquipmentNo + "/costmap.bag"
- var command []string
- command = append(command, "record")
- command = append(command, "-O")
- command = append(command, config.CloudConfig.MapBagPath)
- command = append(command, "-l")
- command = append(command, "1")
- command = append(command, "/move_base/global_costmap/costmap")
- _, s, err := util.ExecuteWithEnvAndDir(config.RosbagEnvs, config.CloudConfig.BagDataDir, config.RosbagPath, command...)
- if err != nil {
- c_log.GlobalLogger.Error("程序异常退出。采集/move_base/global_costmap/costmap包", command, "出错:", s, "----", err)
- os.Exit(-1)
- }
- c_log.GlobalLogger.Error("采集/move_base/global_costmap/costmap包", command, "完成。")
- config.OssMutex.Lock()
- err = config.OssBucket.PutObjectFromFile(ossMapBagObjectKey, config.CloudConfig.MapBagPath)
- config.OssMutex.Unlock()
- if err != nil {
- c_log.GlobalLogger.Error("程序异常退出。上传/move_base/global_costmap/costmap包", config.CloudConfig.MapBagPath, "->", ossMapBagObjectKey, "出错:", err)
- os.Exit(-1)
- }
- c_log.GlobalLogger.Error("上传/move_base/global_costmap/costmap包", config.CloudConfig.MapBagPath, "------", ossMapBagObjectKey, "成功。")
- }
|