提交 35f829e0 编写于 作者: F fanzhu1985 提交者: Capri2014

bazel for graph (#321)

上级 2bb312f8
......@@ -28,10 +28,10 @@ TEST(FileUtilsTestSuit, test1) {
std::string file_path = "./test.bin";
std::string map_version = "versionA";
::apollo::routing::common::Graph graph_1;
::apollo::routing::Graph graph_1;
graph_1.set_hdmap_version(map_version);
::apollo::routing::common::Graph graph_2;
::apollo::routing::Graph graph_2;
ASSERT_TRUE(FileUtils::dump_protobuf_data_to_file(file_path, graph_1));
ASSERT_TRUE(FileUtils::load_protobuf_data_from_file(file_path, &graph_2));
ASSERT_EQ(map_version, graph_2.hdmap_version());
......
/******************************************************************************
* 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/routing/graph/topo_edge.h"
#include "modules/routing/graph/topo_node.h"
#include <math.h>
namespace apollo{
namespace routing {
using ::apollo::routing::common::Edge;
TopoEdge::TopoEdge(const ::apollo::routing::common::Edge& edge,
const TopoNode* from_node, const TopoNode* to_node)
: _pb_edge(edge), _from_node(from_node), _to_node(to_node) {}
TopoEdge::~TopoEdge() {}
const Edge& TopoEdge::edge() const { return _pb_edge; }
double TopoEdge::cost() const { return _pb_edge.cost(); }
const TopoNode* TopoEdge::from_node() const { return _from_node; }
const TopoNode* TopoEdge::to_node() const { return _to_node; }
const std::string& TopoEdge::from_lane_id() const {
return _pb_edge.from_lane_id();
}
const std::string& TopoEdge::to_lane_id() const {
return _pb_edge.to_lane_id();
}
TopoEdgeType TopoEdge::type() const {
if (_pb_edge.direction_type() == ::apollo::routing::common::Edge::LEFT) {
return TET_LEFT;
}
if (_pb_edge.direction_type() == ::apollo::routing::common::Edge::RIGHT) {
return TET_RIGHT;
}
return TET_FORWARD;
}
} // namespace routing
} // namespace apollo
/******************************************************************************
* 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.
*****************************************************************************/
#ifndef MODULES_ROUTING_GRAPH_TOPO_EDGE_H
#define MODULES_ROUTING_GRAPH_TOPO_EDGE_H
#include "map_lane.pb.h"
#include "topo_graph.pb.h"
namespace apollo {
namespace routing {
enum TopoEdgeType {
TET_FORWARD,
TET_LEFT,
TET_RIGHT,
};
class TopoNode;
class TopoEdge {
public:
TopoEdge(const ::apollo::routing::common::Edge& edge, const TopoNode* from_node,
const TopoNode* to_node);
~TopoEdge();
const ::apollo::routing::common::Edge& edge() const;
double cost() const;
const std::string& from_lane_id() const;
const std::string& to_lane_id() const;
TopoEdgeType type() const;
const TopoNode* from_node() const;
const TopoNode* to_node() const;
private:
::apollo::routing::common::Edge _pb_edge;
const TopoNode* _from_node;
const TopoNode* _to_node;
};
} // namespace routing
} // namespace apollo
#endif // MODULES_ROUTING_GRAPH_TOPO_EDGE_H
......@@ -16,7 +16,6 @@
#include "modules/routing/graph/topo_graph.h"
#include "modules/routing/common/utils.h"
#include "modules/routing/graph/topo_edge.h"
#include "modules/routing/graph/topo_node.h"
namespace apollo {
......@@ -28,9 +27,9 @@ void TopoGraph::clear() {
_node_index_map.clear();
}
bool TopoGraph::load_nodes(const ::apollo::routing::common::Graph& graph) {
bool TopoGraph::load_nodes(const ::apollo::routing::Graph& graph) {
if (graph.node_size() == 0) {
ROS_ERROR("No nodes found in topology graph.");
AERROR << "No nodes found in topology graph.";
return false;
}
for (const auto& node : graph.node()) {
......@@ -44,9 +43,9 @@ bool TopoGraph::load_nodes(const ::apollo::routing::common::Graph& graph) {
}
// Need to execute load_nodes() firstly
bool TopoGraph::load_edges(const ::apollo::routing::common::Graph& graph) {
bool TopoGraph::load_edges(const ::apollo::routing::Graph& graph) {
if (graph.edge_size() == 0) {
ROS_ERROR("No edges found in topology graph.");
AERROR << "No edges found in topology graph.";
return false;
}
for (const auto& edge : graph.edge()) {
......@@ -54,8 +53,6 @@ bool TopoGraph::load_edges(const ::apollo::routing::common::Graph& graph) {
const std::string& to_lane_id = edge.to_lane_id();
if (_node_index_map.count(from_lane_id) != 1 ||
_node_index_map.count(to_lane_id) != 1) {
ROS_ERROR("Can't find edge: %s -> %s.", from_lane_id.c_str(),
to_lane_id.c_str());
return false;
}
std::shared_ptr<TopoEdge> topo_edge;
......@@ -72,24 +69,22 @@ bool TopoGraph::load_edges(const ::apollo::routing::common::Graph& graph) {
bool TopoGraph::load_graph(const std::string& file_path) {
clear();
::apollo::routing::common::Graph graph;
::apollo::routing::Graph graph;
if (!::apollo::routing::FileUtils::load_protobuf_data_from_file(file_path,
&graph)) {
ROS_ERROR("Failed to read topology graph from data.");
AERROR << "Failed to read topology graph from data.";
return false;
}
_map_version = graph.hdmap_version();
_map_district = graph.hdmap_district();
ROS_INFO("Use map district: %s, version: %s", _map_district.c_str(),
_map_version.c_str());
if (!load_nodes(graph)) {
ROS_ERROR("Failed to load nodes from topology graph.");
AERROR << "Failed to load nodes from topology graph.";
return false;
}
if (!load_edges(graph)) {
ROS_ERROR("Failed to load edges from topology graph.");
AERROR << "Failed to load edges from topology graph.";
return false;
}
return true;
......@@ -117,4 +112,4 @@ void TopoGraph::get_nodes_by_road_id(
}
} // namespace routing
} // namespace apollo
\ No newline at end of file
} // namespace apollo
......@@ -22,7 +22,8 @@
#include <unordered_set>
#include <vector>
#include "modules/routing/graph/topo_graph.pb.h"
#include "modules/routing/proto/topo_graph.pb.h"
#include "modules/common/log.h"
namespace apollo {
namespace routing {
......@@ -46,8 +47,8 @@ class TopoGraph {
private:
void clear();
bool load_nodes(const ::apollo::routing::common::Graph& graph);
bool load_edges(const ::apollo::routing::common::Graph& graph);
bool load_nodes(const ::apollo::routing::Graph& graph);
bool load_edges(const ::apollo::routing::Graph& graph);
private:
std::string _map_version;
......
......@@ -18,15 +18,13 @@
#include <math.h>
#include "modules/routing/graph/topo_edge.h"
namespace apollo {
namespace routing {
namespace {
using ::apollo::routing::common::Node;
using ::apollo::routing::common::Edge;
using ::apollo::routing::Node;
using ::apollo::routing::Edge;
} // namespace
......@@ -63,11 +61,11 @@ const std::string& TopoNode::lane_id() const { return _pb_node.lane_id(); }
const std::string& TopoNode::road_id() const { return _pb_node.road_id(); }
const ::apollo::common::hdmap::Curve& TopoNode::central_curve() const {
const ::apollo::hdmap::Curve& TopoNode::central_curve() const {
return _pb_node.central_curve();
}
const ::apollo::common::hdmap::Point& TopoNode::anchor_point() const {
const ::apollo::common::PointENU& TopoNode::anchor_point() const {
return _anchor_point;
}
......@@ -194,5 +192,36 @@ void TopoNode::set_start_s(double start_s) { _start_s = start_s; }
void TopoNode::set_end_s(double end_s) { _end_s = end_s; }
TopoEdge::TopoEdge(const ::apollo::routing::Edge& edge,
const TopoNode* from_node, const TopoNode* to_node)
: _pb_edge(edge), _from_node(from_node), _to_node(to_node) {}
TopoEdge::~TopoEdge() {}
const Edge& TopoEdge::edge() const { return _pb_edge; }
double TopoEdge::cost() const { return _pb_edge.cost(); }
const TopoNode* TopoEdge::from_node() const { return _from_node; }
const TopoNode* TopoEdge::to_node() const { return _to_node; }
const std::string& TopoEdge::from_lane_id() const {
return _pb_edge.from_lane_id();
}
const std::string& TopoEdge::to_lane_id() const {
return _pb_edge.to_lane_id();
}
TopoEdgeType TopoEdge::type() const {
if (_pb_edge.direction_type() == ::apollo::routing::Edge::LEFT) {
return TET_LEFT;
}
if (_pb_edge.direction_type() == ::apollo::routing::Edge::RIGHT) {
return TET_RIGHT;
}
return TET_FORWARD;
}
} // namespace routing
} // namespace apollo
......@@ -20,8 +20,8 @@
#include <unordered_map>
#include <unordered_set>
#include "modules/routing/graph/map_lane.pb.h"
#include "modules/routing/graph/topo_graph.pb.h"
#include "modules/map/proto/map_lane.pb.h"
#include "modules/routing/proto/topo_graph.pb.h"
namespace apollo {
namespace routing {
......@@ -30,20 +30,20 @@ class TopoEdge;
class TopoNode {
public:
explicit TopoNode(const ::apollo::routing::common::Node& node);
explicit TopoNode(const ::apollo::routing::Node& node);
explicit TopoNode(const TopoNode* topo_node);
~TopoNode();
const ::apollo::routing::common::Node& node() const;
const ::apollo::routing::Node& node() const;
double length() const;
double cost() const;
bool is_virtual() const;
const std::string& lane_id() const;
const std::string& road_id() const;
const ::apollo::common::hdmap::Curve& central_curve() const;
const ::apollo::common::hdmap::Point& anchor_point() const;
const ::apollo::hdmap::Curve& central_curve() const;
const ::apollo::common::PointENU& anchor_point() const;
const std::unordered_set<const TopoEdge*>& in_from_all_edge() const;
const std::unordered_set<const TopoEdge*>& in_from_left_edge() const;
......@@ -71,8 +71,8 @@ class TopoNode {
void set_end_s(double end_s);
private:
::apollo::routing::common::Node _pb_node;
::apollo::common::hdmap::Point _anchor_point;
::apollo::routing::Node _pb_node;
::apollo::common::PointENU _anchor_point;
double _start_s;
double _end_s;
......@@ -94,6 +94,34 @@ class TopoNode {
const TopoNode* _origin_node;
};
enum TopoEdgeType {
TET_FORWARD,
TET_LEFT,
TET_RIGHT,
};
class TopoEdge {
public:
TopoEdge(const ::apollo::routing::Edge& edge, const TopoNode* from_node,
const TopoNode* to_node);
~TopoEdge();
const ::apollo::routing::Edge& edge() const;
double cost() const;
const std::string& from_lane_id() const;
const std::string& to_lane_id() const;
TopoEdgeType type() const;
const TopoNode* from_node() const;
const TopoNode* to_node() const;
private:
::apollo::routing::Edge _pb_edge;
const TopoNode* _from_node;
const TopoNode* _to_node;
};
} // namespace routing
} // namespace apollo
......
syntax = "proto2";
package apollo.routing.common;
package apollo.routing;
import "modules/map/proto/map_geometry.proto";
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册