提交 e65230a0 编写于 作者: A Aaron Xiao 提交者: Jiangtao Hu

Map: Rename BaseMap getters.

上级 e58b8387
......@@ -59,7 +59,7 @@ class RosBridge {
apollo::hdmap::EndWayPointFile(),
routing_request_template.mutable_end()));
// Init HDMap.
CHECK(HDMapUtil::BaseMap());
CHECK(HDMapUtil::BaseMapPtr());
}
private:
......@@ -132,7 +132,7 @@ class RosBridge {
apollo::hdmap::LaneInfoConstPtr lane = nullptr;
double s, l;
HDMapUtil::BaseMapRef().GetNearestLane(pos, &lane, &s, &l);
HDMapUtil::BaseMap().GetNearestLane(pos, &lane, &s, &l);
if (lane == nullptr) {
AERROR << "Cannot get nearest lane from current position.";
return;
......
......@@ -65,7 +65,7 @@ std::unique_ptr<HDMap> CreateMap(const std::string& map_file_path) {
std::unique_ptr<HDMap> HDMapUtil::base_map_ = nullptr;
std::mutex HDMapUtil::base_map_mutex_;
const HDMap* HDMapUtil::BaseMap() {
const HDMap* HDMapUtil::BaseMapPtr() {
if (base_map_ == nullptr) {
std::lock_guard<std::mutex> lock(base_map_mutex_);
if (base_map_ == nullptr) { // Double check.
......@@ -75,8 +75,8 @@ const HDMap* HDMapUtil::BaseMap() {
return base_map_.get();
}
const HDMap& HDMapUtil::BaseMapRef() {
return *CHECK_NOTNULL(BaseMap());
const HDMap& HDMapUtil::BaseMap() {
return *CHECK_NOTNULL(BaseMapPtr());
}
bool HDMapUtil::ReloadBaseMap() {
......
......@@ -76,10 +76,10 @@ class HDMapUtil {
public:
// Get default base map from the file specified by global flags.
// Return nullptr if failed to load.
static const HDMap* BaseMap();
static const HDMap* BaseMapPtr();
// Similar to BaseMap(), but garantee to return a valid HDMap, or else raise
// fatal error.
static const HDMap& BaseMapRef();
static const HDMap& BaseMap();
// Reload the base map from the file specified by global flags.
static bool ReloadBaseMap();
......
......@@ -60,19 +60,19 @@ do { \
class MapUtil {
public:
const OverlapInfo *get_overlap(const std::string &overlap_id) {
auto ret = HDMapUtil::BaseMapRef().GetOverlapById(MakeMapId(overlap_id));
auto ret = HDMapUtil::BaseMap().GetOverlapById(MakeMapId(overlap_id));
AERROR_IF(ret == nullptr) << "failed to find overlap[" << overlap_id << "]";
return ret.get();
}
const SignalInfo *get_signal(const std::string &signal_id) {
auto ret = HDMapUtil::BaseMapRef().GetSignalById(MakeMapId(signal_id));
auto ret = HDMapUtil::BaseMap().GetSignalById(MakeMapId(signal_id));
AERROR_IF(ret == nullptr) << "failed to find overlap[" << signal_id << "]";
return ret.get();
}
const LaneInfo *get_lane(const std::string &lane_id) {
auto ret = HDMapUtil::BaseMapRef().GetLaneById(MakeMapId(lane_id));
auto ret = HDMapUtil::BaseMap().GetLaneById(MakeMapId(lane_id));
AERROR_IF(ret == nullptr) << "failed to find lane[" << lane_id << "]";
return ret.get();
}
......@@ -83,7 +83,7 @@ class MapUtil {
QUIT_IF(s == nullptr, -2, ERROR, "arg s is null");
QUIT_IF(l == nullptr, -3, ERROR, "arg l is null");
LaneInfoConstPtr lane = nullptr;
int ret = HDMapUtil::BaseMapRef().GetNearestLane(point, &lane, s, l);
int ret = HDMapUtil::BaseMap().GetNearestLane(point, &lane, s, l);
QUIT_IF(ret != 0, -4, ERROR, "get_nearest_lane failed with ret[%d]", ret);
QUIT_IF(lane == nullptr, -5, ERROR, "lane is null");
*lane_id = lane->id().id();
......@@ -94,7 +94,7 @@ class MapUtil {
PointENU *point, double *heading) {
QUIT_IF(point == nullptr, -1, ERROR, "arg point is null");
QUIT_IF(heading == nullptr, -2, ERROR, "arg heading is null");
const auto lane = HDMapUtil::BaseMapRef().GetLaneById(MakeMapId(lane_id));
const auto lane = HDMapUtil::BaseMap().GetLaneById(MakeMapId(lane_id));
QUIT_IF(lane == nullptr, -3, ERROR,
"get_smooth_point_from_lane[%s] failed", lane_id.c_str());
*point = lane->get_smooth_point(s);
......@@ -105,7 +105,7 @@ class MapUtil {
const std::string &lane_id,
double *s, double *l) {
QUIT_IF(s == nullptr, -1, ERROR, "arg s is nullptr");
const auto lane = HDMapUtil::BaseMapRef().GetLaneById(MakeMapId(lane_id));
const auto lane = HDMapUtil::BaseMap().GetLaneById(MakeMapId(lane_id));
QUIT_IF(lane == nullptr, -2, ERROR,
"get_lane_by_id[%s] failed", lane_id.c_str());
bool ret = lane->get_projection(vec2d, s, l);
......
......@@ -36,8 +36,7 @@ namespace hdmap {
apollo::common::PointENU SLToXYZ(const std::string& lane_id,
const double s, const double l) {
const auto lane_info = HDMapUtil::BaseMapRef().GetLaneById(
MakeMapId(lane_id));
const auto lane_info = HDMapUtil::BaseMap().GetLaneById(MakeMapId(lane_id));
CHECK(lane_info);
return lane_info->get_smooth_point(s);
}
......@@ -49,7 +48,7 @@ void XYZToSL(const apollo::common::PointENU& point,
CHECK(l);
LaneInfoConstPtr lane = nullptr;
CHECK_EQ(HDMapUtil::BaseMapRef().GetNearestLane(point, &lane, s, l), 0);
CHECK_EQ(HDMapUtil::BaseMap().GetNearestLane(point, &lane, s, l), 0);
*lane_id = lane->id().id();
}
......
......@@ -54,7 +54,7 @@ bool HDMapInput::Init() {
}
bool HDMapInput::GetROI(const PointD& pointd, HdmapStructPtr* mapptr) {
auto* hdmap = HDMapUtil::BaseMap();
auto* hdmap = HDMapUtil::BaseMapPtr();
if (hdmap == nullptr) {
return false;
}
......
......@@ -61,7 +61,7 @@ double PredictionMap::LaneTotalWidth(
std::shared_ptr<const LaneInfo> PredictionMap::LaneById(
const std::string& str_id) {
return HDMapUtil::BaseMapRef().GetLaneById(apollo::hdmap::MakeMapId(str_id));
return HDMapUtil::BaseMap().GetLaneById(apollo::hdmap::MakeMapId(str_id));
}
bool PredictionMap::GetProjection(const Eigen::Vector2d& position,
......@@ -97,7 +97,7 @@ void PredictionMap::OnLane(
apollo::common::PointENU hdmap_point;
hdmap_point.set_x(point[0]);
hdmap_point.set_y(point[1]);
if (HDMapUtil::BaseMapRef().GetLanesWithHeading(
if (HDMapUtil::BaseMap().GetLanesWithHeading(
hdmap_point, radius, heading, M_PI, &candidate_lanes) != 0) {
return;
}
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册