sensor_manager.cc 7.5 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18
/******************************************************************************
 * Copyright 2018 The Apollo Authors. All Rights Reserved.
 *
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 * http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 *****************************************************************************/
#include "modules/perception/common/sensor_manager/sensor_manager.h"

#include <string>
19
#include <utility>
20

G
GoLancer 已提交
21
#include "cyber/common/log.h"
22 23
#include "modules/common/util/file.h"
#include "modules/perception/common/io/io_util.h"
24 25
#include "modules/perception/lib/config_manager/config_manager.h"
#include "modules/perception/lib/io/file_util.h"
26
#include "modules/perception/proto/sensor_meta_schema.pb.h"
27 28 29 30 31

namespace apollo {
namespace perception {
namespace common {

32
using apollo::common::util::GetProtoFromASCIIFile;
33 34 35 36
using apollo::perception::base::BrownCameraDistortionModel;
using apollo::perception::base::SensorInfo;
using apollo::perception::base::SensorOrientation;
using apollo::perception::base::SensorType;
37

38
SensorManager::SensorManager() { CHECK_EQ(this->Init(), true); }
39 40 41 42 43 44 45 46 47 48 49 50

bool SensorManager::Init() {
  std::lock_guard<std::mutex> lock(mutex_);
  if (inited_) {
    return true;
  }

  sensor_info_map_.clear();
  distort_model_map_.clear();
  undistort_model_map_.clear();

  std::string file_path = lib::FileUtil::GetAbsolutePath(
51
      lib::ConfigManager::Instance()->work_root(), FLAGS_obs_sensor_meta_path);
52 53

  MultiSensorMeta sensor_list_proto;
54 55 56
  if (!GetProtoFromASCIIFile(file_path, &sensor_list_proto)) {
    AERROR << "Invalid MultiSensorMeta file: "
           << FLAGS_obs_sensor_meta_path;
57 58 59 60
    return false;
  }

  auto AddSensorInfo = [this](const SensorMeta& sensor_meta_proto) {
61
    SensorInfo sensor_info;
62
    sensor_info.name = sensor_meta_proto.name();
63
    sensor_info.type = static_cast<SensorType>(sensor_meta_proto.type());
64
    sensor_info.orientation =
65
        static_cast<SensorOrientation>(sensor_meta_proto.orientation());
66 67 68 69 70
    sensor_info.frame_id = sensor_meta_proto.name();

    auto pair = sensor_info_map_.insert(
        make_pair(sensor_meta_proto.name(), sensor_info));
    if (!pair.second) {
71
      AERROR << "Duplicate sensor name error.";
72 73 74 75
      return false;
    }

    if (this->IsCamera(sensor_info.type)) {
76 77
      std::shared_ptr<BrownCameraDistortionModel> distort_model(
          new BrownCameraDistortionModel());
78 79
      if (!LoadBrownCameraIntrinsic(IntrinsicPath(sensor_info.frame_id),
                                    distort_model.get())) {
80
        AERROR << "Failed to load camera intrinsic";
81 82
        return false;
      }
83 84 85
      distort_model_map_.insert(make_pair(
          sensor_meta_proto.name(),
          std::dynamic_pointer_cast<BaseCameraDistortionModel>(distort_model)));
86 87 88 89 90 91 92 93
      undistort_model_map_.insert(make_pair(sensor_meta_proto.name(),
                                            distort_model->get_camera_model()));
    }
    return true;
  };

  for (const SensorMeta& sensor_meta_proto : sensor_list_proto.sensor_meta()) {
    if (!AddSensorInfo(sensor_meta_proto)) {
94
      AERROR << "Failed to add sensor_info: " << sensor_meta_proto.name();
95 96 97 98 99
      return false;
    }
  }

  inited_ = true;
100
  AINFO << "Init sensor_manager success.";
101 102 103 104 105 106 107 108 109 110 111 112 113
  return true;
}

bool SensorManager::IsSensorExist(const std::string& name) const {
  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return false;
  } else {
    return true;
  }
}

bool SensorManager::GetSensorInfo(const std::string& name,
114
                                  SensorInfo* sensor_info) const {
115
  if (sensor_info == nullptr) {
116
    AERROR << "Nullptr error.";
117 118 119 120 121 122 123 124 125 126 127 128
    return false;
  }

  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return false;
  } else {
    *sensor_info = itr->second;
  }
  return true;
}

129
std::shared_ptr<BaseCameraDistortionModel> SensorManager::GetDistortCameraModel(
130 131 132 133 134 135 136 137 138
    const std::string& name) const {
  const auto& itr = distort_model_map_.find(name);
  if (itr == distort_model_map_.end()) {
    return nullptr;
  } else {
    return itr->second;
  }
}

139
std::shared_ptr<BaseCameraModel> SensorManager::GetUndistortCameraModel(
140 141 142 143 144 145 146 147 148 149 150 151 152 153
    const std::string& name) const {
  const auto& itr = undistort_model_map_.find(name);
  if (itr == undistort_model_map_.end()) {
    return nullptr;
  } else {
    return itr->second;
  }
}

bool SensorManager::IsHdLidar(const std::string& name) const {
  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return false;
  } else {
154
    SensorType type = itr->second.type;
155 156 157 158
    return this->IsHdLidar(type);
  }
}

159
bool SensorManager::IsHdLidar(const SensorType& type) const {
Z
ZhaozhengPlus 已提交
160 161 162
  return type == SensorType::VELODYNE_128 ||
         type == SensorType::VELODYNE_64 ||
         type == SensorType::VELODYNE_32 ||
163
         type == SensorType::VELODYNE_16;
164 165 166 167 168 169 170
}

bool SensorManager::IsLdLidar(const std::string& name) const {
  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return false;
  } else {
171
    SensorType type = itr->second.type;
172 173 174 175
    return this->IsLdLidar(type);
  }
}

176
bool SensorManager::IsLdLidar(const SensorType& type) const {
177
  return type == SensorType::LDLIDAR_4 || type == SensorType::LDLIDAR_1;
178 179 180 181 182 183 184
}

bool SensorManager::IsLidar(const std::string& name) const {
  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return false;
  } else {
185
    SensorType type = itr->second.type;
186 187 188 189
    return this->IsLidar(type);
  }
}

190
bool SensorManager::IsLidar(const SensorType& type) const {
191 192 193 194 195 196 197 198
  return this->IsHdLidar(type) || this->IsLdLidar(type);
}

bool SensorManager::IsRadar(const std::string& name) const {
  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return false;
  } else {
199
    SensorType type = itr->second.type;
200 201 202 203
    return this->IsRadar(type);
  }
}

204 205 206
bool SensorManager::IsRadar(const SensorType& type) const {
  return type == SensorType::SHORT_RANGE_RADAR ||
         type == SensorType::LONG_RANGE_RADAR;
207 208 209 210 211 212 213
}

bool SensorManager::IsCamera(const std::string& name) const {
  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return false;
  } else {
214
    SensorType type = itr->second.type;
215 216 217 218
    return this->IsCamera(type);
  }
}

219 220 221
bool SensorManager::IsCamera(const SensorType& type) const {
  return type == SensorType::MONOCULAR_CAMERA ||
         type == SensorType::STEREO_CAMERA;
222 223 224 225 226 227 228
}

bool SensorManager::IsUltrasonic(const std::string& name) const {
  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return false;
  } else {
229
    SensorType type = itr->second.type;
230 231 232 233
    return this->IsUltrasonic(type);
  }
}

234 235
bool SensorManager::IsUltrasonic(const SensorType& type) const {
  return type == SensorType::ULTRASONIC;
236 237 238 239 240 241 242 243 244 245 246 247 248 249
}

std::string SensorManager::GetFrameId(const std::string& name) const {
  const auto& itr = sensor_info_map_.find(name);
  if (itr == sensor_info_map_.end()) {
    return std::string("");
  } else {
    return itr->second.frame_id;
  }
}

}  // namespace common
}  // namespace perception
}  // namespace apollo