提交 2fceb8e0 编写于 作者: A Aaron Xiao 提交者: Dong Li

Map: Move global HDMap singleton to hdmap_util.

上级 f5f1ad80
......@@ -13,7 +13,7 @@ cc_binary(
"//modules/common/adapters:adapter_manager",
"//modules/control/common",
"//modules/control/proto:control_proto",
"//modules/map/hdmap",
"//modules/map/hdmap:hdmap_util",
"@ros//:ros_common",
],
)
......
......@@ -25,7 +25,7 @@
#include "modules/common/util/file.h"
#include "modules/control/common/control_gflags.h"
#include "modules/control/proto/pad_msg.pb.h"
#include "modules/map/hdmap/hdmap.h"
#include "modules/map/hdmap/hdmap_util.h"
DEFINE_string(adapter_config_file,
......@@ -40,7 +40,7 @@ using apollo::common::adapter::AdapterManager;
using apollo::common::adapter::AdapterManagerConfig;
using apollo::control::DrivingAction;
using apollo::canbus::Chassis;
using apollo::hdmap::HDMap;
using apollo::hdmap::HDMapUtil;
namespace apollo {
namespace hmi {
......@@ -62,7 +62,7 @@ class RosBridge {
CHECK(apollo::common::util::GetProtoFromASCIIFile(
FLAGS_routing_request_template, &routing_request_template));
// Init HDMap.
hdmap_ = &HDMap::DefaultMap();
CHECK(HDMapUtil::instance()->BaseMap());
}
private:
......@@ -134,7 +134,8 @@ class RosBridge {
// Look up lane info from map.
apollo::hdmap::LaneInfoConstPtr lane = nullptr;
double s, l;
hdmap_->get_nearest_lane(pos, &lane, &s, &l);
HDMapUtil::instance()->BaseMapRef().get_nearest_lane(pos, &lane, &s, &l);
if (lane == nullptr) {
AERROR << "Cannot get nearest lane from current position.";
return;
......@@ -155,7 +156,6 @@ class RosBridge {
}
private:
const HDMap* hdmap_;
routing::RoutingRequest routing_request_template;
DECLARE_SINGLETON(RosBridge);
......
......@@ -26,6 +26,19 @@ cc_library(
],
)
cc_library(
name = "hdmap_util",
srcs = ["hdmap_util.cc"],
hdrs = ["hdmap_util.h"],
deps = [
":hdmap",
"//modules/common:log",
"//modules/common:macro",
"//modules/common/configs:config_gflags",
"//modules/common/util:string_util",
],
)
filegroup(
name = "testdata",
srcs = glob([
......
......@@ -20,18 +20,6 @@ limitations under the License.
namespace apollo {
namespace hdmap {
std::unique_ptr<HDMap> HDMap::CreateMap(const std::string& map_filename) {
std::unique_ptr<HDMap> hdmap(new HDMap());
CHECK_EQ(hdmap->load_map_from_file(map_filename), 0)
<< "Failed to load HDMap " << map_filename;
return hdmap;
}
const HDMap& HDMap::DefaultMap() {
static const HDMap* hdmap = CreateMap(BaseMapFile()).release();
return *hdmap;
}
int HDMap::load_map_from_file(const std::string& map_filename) {
return _impl.load_map_from_file(map_filename);
}
......
......@@ -48,11 +48,6 @@ namespace hdmap {
*/
class HDMap {
public:
static std::unique_ptr<HDMap> CreateMap(const std::string& map_filename);
// Get default map loaded from the file specified by BaseMapFile().
static const HDMap& DefaultMap();
/**
* @brief load map from local file
* @param map_filename path of map data file
......
/* Copyright 2017 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/map/hdmap/hdmap_util.h"
namespace apollo {
namespace hdmap {
std::unique_ptr<HDMap> CreateMap(const std::string& map_file_path) {
std::unique_ptr<HDMap> hdmap(new HDMap());
if (hdmap->load_map_from_file(map_file_path) != 0) {
AERROR << "Failed to load HDMap " << map_file_path;
hdmap.reset(nullptr);
}
return hdmap;
}
HDMapUtil::HDMapUtil() {}
const HDMap* HDMapUtil::BaseMap() {
if (base_map_ == nullptr) {
std::lock_guard<std::mutex> lock(base_map_mutex_);
if (base_map_ == nullptr) { // Double check.
base_map_ = CreateMap(BaseMapFile());
}
}
return base_map_.get();
}
const HDMap& HDMapUtil::BaseMapRef() {
return *CHECK_NOTNULL(BaseMap());
}
bool HDMapUtil::ReloadBaseMap() {
std::lock_guard<std::mutex> lock(base_map_mutex_);
base_map_ = CreateMap(BaseMapFile());
return base_map_ != nullptr;
}
} // namespace hdmap
} // namespace apollo
......@@ -16,10 +16,12 @@ limitations under the License.
#ifndef MODULES_MAP_HDMAP_HDMAP_UTIL_H
#define MODULES_MAP_HDMAP_HDMAP_UTIL_H
#include <mutex>
#include <string>
#include "modules/common/configs/config_gflags.h"
#include "modules/common/util/string_util.h"
#include "modules/map/hdmap/hdmap.h"
#include "modules/map/proto/map_id.pb.h"
/**
......@@ -67,6 +69,27 @@ inline apollo::hdmap::Id MakeMapId(const std::string& id) {
return map_id;
}
std::unique_ptr<HDMap> CreateMap(const std::string& map_file_path);
class HDMapUtil {
public:
// Get default base map from the file specified by global flags.
// Return nullptr if failed to load.
const HDMap* BaseMap();
// Similar to BaseMap(), but garantee to return a valid HDMap, or else raise
// fatal error.
const HDMap& BaseMapRef();
// Reload the base map from the file specified by global flags.
bool ReloadBaseMap();
private:
std::unique_ptr<HDMap> base_map_ = nullptr;
std::mutex base_map_mutex_;
DECLARE_SINGLETON(HDMapUtil);
};
} // namespace hdmap
} // namespace apollo
......
......@@ -11,6 +11,7 @@ cc_library(
"//modules/common:log",
"//modules/common/configs:config_gflags",
"//modules/map/hdmap",
"//modules/map/hdmap:hdmap_util",
"//modules/perception/common:perception_common",
"//modules/perception/lib/base",
"//modules/perception/lib/pcl_util",
......
......@@ -23,6 +23,7 @@
#include "Eigen/Core"
#include "modules/common/configs/config_gflags.h"
#include "modules/common/log.h"
#include "modules/map/hdmap/hdmap_util.h"
#include "modules/perception/common/define.h"
#include "modules/perception/common/perception_gflags.h"
......@@ -36,6 +37,7 @@ using apollo::hdmap::JunctionInfoConstPtr;
using apollo::hdmap::JunctionBoundaryPtr;
using apollo::hdmap::BoundaryEdge_Type_LEFT_BOUNDARY;
using apollo::hdmap::BoundaryEdge_Type_RIGHT_BOUNDARY;
using apollo::hdmap::HDMapUtil;
using apollo::common::math::Vec2d;
using apollo::common::math::Polygon2d;
using pcl_util::PointD;
......@@ -45,10 +47,17 @@ using std::string;
using std::vector;
// HDMapInput
HDMapInput::HDMapInput() {}
HDMapInput::HDMapInput() : hdmap_(apollo::hdmap::HDMap::DefaultMap()) {}
bool HDMapInput::Init() {
return HDMapUtil::instance()->ReloadBaseMap();
}
bool HDMapInput::GetROI(const PointD& pointd, HdmapStructPtr* mapptr) {
auto* hdmap = HDMapUtil::instance()->BaseMap();
if (hdmap == nullptr) {
return false;
}
std::unique_lock<std::mutex> lock(mutex_);
if (mapptr != NULL && *mapptr == nullptr) {
(*mapptr).reset(new HdmapStruct);
......@@ -60,8 +69,8 @@ bool HDMapInput::GetROI(const PointD& pointd, HdmapStructPtr* mapptr) {
std::vector<RoadROIBoundaryPtr> boundary_vec;
std::vector<JunctionBoundaryPtr> junctions_vec;
int status = hdmap_.get_road_boundaries(point, FLAGS_map_radius,
&boundary_vec, &junctions_vec);
int status = hdmap->get_road_boundaries(
point, FLAGS_map_radius, &boundary_vec, &junctions_vec);
if (status != SUCC) {
AERROR << "Failed to get road boundaries for point " << point.DebugString();
return false;
......
......@@ -34,13 +34,13 @@ namespace perception {
// Singleton HDMapInput, interfaces are thread-safe.
class HDMapInput {
public:
bool Init();
// @brief: get roi polygon
// all points are in the world frame
bool GetROI(const pcl_util::PointD& pointd, HdmapStructPtr* mapptr);
private:
HDMapInput();
void DownSampleBoundary(const apollo::hdmap::LineSegment& line,
PolygonDType* out_boundary_line) const;
......@@ -49,15 +49,12 @@ class HDMapInput {
std::vector<apollo::hdmap::JunctionBoundaryPtr>& junctions,
HdmapStructPtr* mapptr);
friend class Singleton<HDMapInput>;
std::mutex mutex_; // multi-thread init safe.
const apollo::hdmap::HDMap& hdmap_;
DISALLOW_COPY_AND_ASSIGN(HDMapInput);
FRIEND_TEST(HDMapInputTest, test_Init);
FRIEND_TEST(HDMapInputTest, test_GetROI);
DECLARE_SINGLETON(HDMapInput);
};
typedef typename std::shared_ptr<HDMapInput> HDMapInputPtr;
......
......@@ -13,26 +13,36 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include <vector>
#include "modules/perception/obstacle/onboard/hdmap_input.h"
#include <vector>
#include "gtest/gtest.h"
#include "modules/common/configs/config_gflags.h"
#include "modules/common/log.h"
#include "modules/perception/common/perception_gflags.h"
#include "modules/perception/obstacle/onboard/hdmap_input.h"
namespace apollo {
namespace perception {
TEST(HDMapInputTest, test_Init) {
auto* hdmap_input = HDMapInput::instance();
EXPECT_TRUE(hdmap_input->Init());
FLAGS_base_map_filename = "not_exit_dir";
EXPECT_FALSE(hdmap_input->Init());
}
TEST(HDMapInputTest, test_GetROI) {
HdmapStructPtr hdmap;
auto* hdmap_input = HDMapInput::instance();
pcl_util::PointD velodyne_pose_world = {
587054.96336391149, 4141606.3593586856, 0.0};
EXPECT_FALSE(hdmap_input->GetROI(velodyne_pose_world, &hdmap));
FLAGS_map_dir = "modules/map/data";
FLAGS_base_map_filename = "sunnyvale_loop.xml.txt";
EXPECT_TRUE(
Singleton<HDMapInput>::Get()->GetROI(velodyne_pose_world, &hdmap));
EXPECT_TRUE(hdmap_input->Init());
EXPECT_TRUE(hdmap_input->GetROI(velodyne_pose_world, &hdmap));
EXPECT_TRUE(hdmap != nullptr);
}
......
......@@ -219,11 +219,15 @@ bool LidarProcess::InitFrameDependence() {
/// init hdmap
if (FLAGS_enable_hdmap_input) {
hdmap_input_ = Singleton<HDMapInput>::Get();
hdmap_input_ = HDMapInput::instance();
if (!hdmap_input_) {
AERROR << "failed to get HDMapInput instance.";
return false;
}
if (!hdmap_input_->Init()) {
AERROR << "failed to init HDMapInput";
return false;
}
AINFO << "get and init hdmap_input succ.";
}
......
......@@ -96,7 +96,7 @@ TEST_F(LidarProcessTest, test_Process) {
}
std::shared_ptr<Matrix4d> velodyne_trans = std::make_shared<Matrix4d>();
(*velodyne_trans) << 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1;
lidar_process_.hdmap_input_ = Singleton<HDMapInput>::Get();
lidar_process_.hdmap_input_ = HDMapInput::instance();
EXPECT_TRUE(lidar_process_.Process(123.0, point_cloud, velodyne_trans));
}
......
......@@ -41,7 +41,7 @@ cc_library(
"//modules/common/configs:config_gflags",
"//modules/common/math:linear_interpolation",
"//modules/common/math:vec2d",
"//modules/map/hdmap",
"//modules/map/hdmap:hdmap_util",
"//modules/map/pnc_map",
"@eigen//:eigen",
],
......
......@@ -26,7 +26,6 @@
#include "modules/common/configs/config_gflags.h"
#include "modules/common/math/linear_interpolation.h"
#include "modules/common/math/vec2d.h"
#include "modules/map/hdmap/hdmap.h"
#include "modules/map/hdmap/hdmap_util.h"
#include "modules/map/proto/map_id.pb.h"
#include "modules/prediction/common/prediction_gflags.h"
......@@ -37,8 +36,9 @@ namespace prediction {
using apollo::hdmap::LaneInfo;
using apollo::hdmap::Id;
using apollo::hdmap::MapPathPoint;
using apollo::hdmap::HDMapUtil;
PredictionMap::PredictionMap() : hdmap_(apollo::hdmap::HDMap::DefaultMap()) {}
PredictionMap::PredictionMap() {}
Eigen::Vector2d PredictionMap::PositionOnLane(
std::shared_ptr<const LaneInfo> lane_info,
......@@ -81,7 +81,7 @@ double PredictionMap::LaneTotalWidth(
}
std::shared_ptr<const LaneInfo> PredictionMap::LaneById(const Id& id) {
return hdmap_.get_lane_by_id(id);
return HDMapUtil::instance()->BaseMapRef().get_lane_by_id(id);
}
std::shared_ptr<const LaneInfo> PredictionMap::LaneById(
......@@ -126,7 +126,7 @@ void PredictionMap::OnLane(
apollo::common::PointENU hdmap_point;
hdmap_point.set_x(point[0]);
hdmap_point.set_y(point[1]);
if (hdmap_.get_lanes_with_heading(
if (HDMapUtil::instance()->BaseMapRef().get_lanes_with_heading(
hdmap_point, radius, heading, M_PI, &candidate_lanes) != 0) {
return;
}
......
......@@ -284,7 +284,6 @@ class PredictionMap {
}
private:
const apollo::hdmap::HDMap& hdmap_;
DECLARE_SINGLETON(PredictionMap);
};
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册