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

Routing: Migrate to get routing map from map_dir.

上级 2871622b
......@@ -24,6 +24,10 @@ DEFINE_string(map_dir, "modules/map/data/new_garage",
DEFINE_string(base_map_filename, "base_map.xml",
"Base map file which locates in the map_dir.");
DEFINE_string(sim_map_filename, "sim_map.bin",
"Simulation map file which locates in the map_dir.");
DEFINE_string(routing_map_filename, "routing_map.bin",
"Routing map file which locates in the map_dir.");
DEFINE_string(vehicle_config_path, "modules/common/data/mkz_config.pb.txt",
"the file path of vehicle config file");
......@@ -25,7 +25,10 @@ DECLARE_string(map_file_path);
// The directory which contains a group of related maps, such as base_map,
// sim_map, routing_topo_grapth, etc.
DECLARE_string(map_dir);
DECLARE_string(base_map_filename);
DECLARE_string(sim_map_filename);
DECLARE_string(routing_map_filename);
DECLARE_string(vehicle_config_path);
......
......@@ -38,6 +38,24 @@ inline std::string BaseMapFile() {
FLAGS_map_dir, "/", FLAGS_base_map_filename);
}
/**
* @brief get simulation map file path from flags.
* @return simulation map path
*/
inline std::string SimMapFile() {
return apollo::common::util::StrCat(
FLAGS_map_dir, "/", FLAGS_sim_map_filename);
}
/**
* @brief get routing map file path from flags.
* @return routing map path
*/
inline std::string RoutingMapFile() {
return apollo::common::util::StrCat(
FLAGS_map_dir, "/", FLAGS_routing_map_filename);
}
/**
* @brief create a Map ID given a string.
* @param id a string id
......
......@@ -17,6 +17,7 @@ cc_library(
"//modules/common/monitor",
"//modules/common/status",
"//modules/common/util",
"//modules/map/hdmap",
"//modules/routing/common:routing_gflags",
"//modules/routing/core",
"//modules/routing/proto:routing_proto",
......
......@@ -21,9 +21,6 @@ DEFINE_string(node_namespace, "routing", "the namespace for this node");
DEFINE_bool(use_road_id, true, "enable use road id to cut routing result");
DEFINE_string(graph_file_path, "modules/map/data/routing_map.txt",
"the default file name of topology graph data");
DEFINE_bool(enable_debug_mode, true, "enable debug mode");
DEFINE_string(debug_route_path, "",
"the default path of routing result debug file");
......
......@@ -24,8 +24,6 @@ DECLARE_string(node_namespace);
DECLARE_bool(use_road_id);
DECLARE_string(graph_file_path);
DECLARE_bool(enable_debug_mode);
DECLARE_string(debug_route_path);
DECLARE_string(debug_passage_region_path);
......
......@@ -17,6 +17,7 @@
#include "modules/routing/routing.h"
#include "modules/common/adapters/adapter_gflags.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/map/hdmap/hdmap_util.h"
#include "modules/routing/common/routing_gflags.h"
#include "modules/routing/core/navigator.h"
......@@ -31,8 +32,9 @@ std::string Routing::Name() const { return FLAGS_node_name; }
Routing::Routing()
: monitor_(apollo::common::monitor::MonitorMessageItem::ROUTING) {
AINFO << "Use routing topology graph path: " << FLAGS_graph_file_path;
navigator_ptr_.reset(new Navigator(FLAGS_graph_file_path));
const auto routing_map_file = apollo::hdmap::RoutingMapFile();
AINFO << "Use routing topology graph path: " << routing_map_file;
navigator_ptr_.reset(new Navigator(routing_map_file));
}
apollo::common::Status Routing::Init() {
......
......@@ -65,6 +65,7 @@ cc_binary(
"//modules/common",
"//modules/common:log",
"//modules/common/configs:config_gflags",
"//modules/map/hdmap",
"//modules/map/proto:map_proto",
"//modules/routing/common:routing_gflags",
"//modules/routing/proto:routing_proto",
......
......@@ -18,19 +18,20 @@
#include "modules/common/configs/config_gflags.h"
#include "modules/common/log.h"
#include "modules/routing/common/routing_gflags.h"
#include "modules/map/hdmap/hdmap_util.h"
#include "modules/routing/topo_creator/graph_creator.h"
int main(int argc, char **argv) {
google::InitGoogleLogging(argv[0]);
google::ParseCommandLineFlags(&argc, &argv, true);
std::unique_ptr<::apollo::routing::GraphCreator> creator_ptr;
creator_ptr.reset(new ::apollo::routing::GraphCreator(FLAGS_map_file_path,
FLAGS_graph_file_path));
const auto routing_map_file = apollo::hdmap::RoutingMapFile();
creator_ptr.reset(new ::apollo::routing::GraphCreator(
apollo::hdmap::BaseMapFile(), routing_map_file));
if (!creator_ptr->Create()) {
AERROR << "Create routing topo failed!";
return -1;
}
AINFO << "Create routing topo successfully from " << FLAGS_graph_file_path;
AINFO << "Create routing topo successfully from " << routing_map_file;
return 0;
}
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册