提交 3610a837 编写于 作者: F fanzhu1985 提交者: henryhu6

routing: fix paths for offline topo (#402)

上级 a2945036
......@@ -26,8 +26,10 @@ DEFINE_string(route_topic_for_broadcast, "/routing/routing",
"the default routing topic");
DEFINE_bool(use_road_id, true, "enable use road id to cut routing result");
DEFINE_string(graph_dir, "", "the default directory of topology graph data");
DEFINE_string(graph_file_name, "routing_map.bin",
DEFINE_string(map_dir, "/apollo/modules/map/data", "the default directory of hdmap");
DEFINE_string(map_file_name, "base_map.txt", "the default file name of hdmap.");
DEFINE_string(graph_dir, "/apollo/modules/map/data", "the default directory of topology graph data");
DEFINE_string(graph_file_name, "routing_map.txt",
"the default file name of topology graph data");
DEFINE_string(rosparam_name_routing_init_status, "/pnc/routing_initialized",
......
......@@ -27,6 +27,8 @@ DECLARE_bool(enable_old_routing);
DECLARE_string(route_topic_for_broadcast);
DECLARE_bool(use_road_id);
DECLARE_string(map_dir);
DECLARE_string(map_file_name);
DECLARE_string(graph_dir);
DECLARE_string(graph_file_name);
......
......@@ -27,23 +27,6 @@ using ::google::protobuf::io::FileInputStream;
using ::google::protobuf::io::ZeroCopyInputStream;
using ::google::protobuf::io::CodedInputStream;
bool FileUtils::load_protobuf_data_from_file(
const std::string& file_path,
::google::protobuf::Message* const proto_data) {
int fd = open(file_path.c_str(), O_RDONLY);
if (fd == -1) {
AERROR << "File %s not found" << file_path.c_str();
return false;
}
std::unique_ptr<ZeroCopyInputStream> raw_input(new FileInputStream(fd));
std::unique_ptr<CodedInputStream> coded_input(
new CodedInputStream(raw_input.get()));
coded_input->SetTotalBytesLimit(INT_MAX, 536870912); // 0..512M..2G
bool ret = proto_data->ParseFromCodedStream(coded_input.get());
close(fd);
return ret;
}
bool FileUtils::dump_protobuf_data_to_file(
const std::string& file_path,
const ::google::protobuf::Message* const proto_data) {
......
......@@ -25,9 +25,6 @@ namespace routing {
class FileUtils {
public:
static bool load_protobuf_data_from_file(
const std::string& file_path,
::google::protobuf::Message* const proto_data);
static bool dump_protobuf_data_to_file(
const std::string& file_path,
const ::google::protobuf::Message& proto_data);
......
......@@ -39,6 +39,7 @@ cc_library(
"//modules/map/proto:map_proto",
"//modules/routing/proto:routing_proto",
"//modules/common:common",
"//modules/common/util",
"//modules/routing/common"
],
)
......
......@@ -17,6 +17,7 @@
#include "modules/routing/graph/topo_graph.h"
#include "modules/routing/common/utils.h"
#include "modules/routing/graph/topo_node.h"
#include "modules/common/util/file.h"
namespace apollo {
namespace routing {
......@@ -70,8 +71,8 @@ bool TopoGraph::load_graph(const std::string& file_path) {
clear();
::apollo::routing::Graph graph;
if (!::apollo::routing::FileUtils::load_protobuf_data_from_file(file_path,
&graph)) {
if (!::apollo::common::util::GetProtoFromFile(
file_path, &graph)) {
AERROR << "Failed to read topology graph from data.";
return false;
}
......
......@@ -34,6 +34,7 @@ cc_library(
"//modules/routing/proto:routing_proto",
"//modules/map/proto:map_proto",
"//modules/common:common",
"//modules/common/util",
"//modules/routing/common"
],
)
......
......@@ -21,6 +21,7 @@
#include "modules/routing/common/utils.h"
#include "modules/routing/topo_creator/edge_creator.h"
#include "modules/routing/topo_creator/node_creator.h"
#include "modules/common/util/file.h"
namespace apollo {
namespace routing {
......@@ -46,7 +47,7 @@ GraphCreator::GraphCreator(const std::string& base_map_file_path,
_dump_topo_file_path(dump_topo_file_path) {}
bool GraphCreator::create() {
if (!::apollo::routing::FileUtils::load_protobuf_data_from_file(
if (!::apollo::common::util::GetProtoFromFile(
_base_map_file_path, &_pbmap)) {
LOG(ERROR) << "Failed to load base map file from " << _base_map_file_path;
return false;
......
......@@ -21,21 +21,19 @@
#include "modules/routing/topo_creator/graph_creator.h"
#include "modules/common/log.h"
DEFINE_string(base_map_dir, "/apollo/modules/map/data", "directory of base map");
DEFINE_string(base_map_name, "base_map.txt", "file name of base map");
DEFINE_string(dump_topo_path, "/apollo/modules/map/data/routing_map.bin", "dump path of routing topology file");
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_base_map_dir + "/" + FLAGS_base_map_name,
FLAGS_dump_topo_path));
FLAGS_map_dir + "/" + FLAGS_map_file_name,
FLAGS_graph_dir + "/" + FLAGS_graph_file_name));
if (!creator_ptr->create()) {
AERROR << "Create router topo failed!";
AERROR << "Create routing topo failed!";
return -1;
}
LOG(INFO) << "Create routing topo succesful!";
LOG(INFO) << FLAGS_graph_dir + "/" + FLAGS_graph_file_name;
return 0;
}
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册