Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
RoutingGraphAccessor Class Reference

This class serves as a method of exposing the internal protected members of the lanelet2 RoutingGraph. This allows for a conversion method to be written which converts the routing graph to a ROS message representation. More...

#include <RoutingGraphAccessor.hpp>

Inheritance diagram for RoutingGraphAccessor:
Inheritance graph
Collaboration diagram for RoutingGraphAccessor:
Collaboration graph

Public Member Functions

autoware_lanelet2_msgs::msg::RoutingGraph routingGraphToMsg (const std::string &participant)
 Returns a ROS message version of this RoutingGraph. This is done by accessing protected data members directly. More...
 

Detailed Description

This class serves as a method of exposing the internal protected members of the lanelet2 RoutingGraph. This allows for a conversion method to be written which converts the routing graph to a ROS message representation.

ASSUMPTION: Note this class is heavily dependant on the non-public implementation API of lanelet2 (v1.1.1). Any change to the underlying data structures may negatively impact this classes performance or ability to compile.

Definition at line 32 of file RoutingGraphAccessor.hpp.

Member Function Documentation

◆ routingGraphToMsg()

autoware_lanelet2_msgs::msg::RoutingGraph RoutingGraphAccessor::routingGraphToMsg ( const std::string &  participant)
inline

Returns a ROS message version of this RoutingGraph. This is done by accessing protected data members directly.

Parameters
participantThe participant which was used to build this routing graph. NOTE: This is not a choice. This must match the value used to generate this object.
Returns
The ros message which can be used to regenerate this routing graph structure.

Definition at line 44 of file RoutingGraphAccessor.hpp.

44 {
45
46
47 autoware_lanelet2_msgs::msg::RoutingGraph msg; // output message
48
49 // Assign base fields
50 msg.num_unique_routing_cost_ids = this->graph_->numRoutingCosts();
51 msg.participant_type = participant;
52
53 // Get the underlying graph
54 // Type will be boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo>
55 // As version of lanelet2 used when writing this function
56 auto underlying_graph = this->graph_->get();
57
58 // Iterate over all vertices in the graph
59 boost::graph_traits<lanelet::routing::internal::GraphType>::vertex_iterator vi, vi_end;
60
61 for(boost::tie(vi, vi_end) = boost::vertices(underlying_graph); vi != vi_end; ++vi) {
62
63 autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges vertex_and_edges;
64
65 lanelet::routing::internal::GraphType::vertex_descriptor source = *vi;
66
67 // Iterate over all outgoing edges for this vertex
68 boost::graph_traits<lanelet::routing::internal::GraphType>::out_edge_iterator ei, ei_end;
69 for(boost::tie(ei, ei_end) = boost::out_edges(source, underlying_graph); ei != ei_end; ++ei) {
70
71 lanelet::routing::internal::GraphType::edge_descriptor edge = *ei;
72 lanelet::routing::internal::GraphType::vertex_descriptor target = boost::target(edge, underlying_graph);
73
74
75 // Populate the edge info in the message
76 vertex_and_edges.lanelet_or_area_ids.push_back(underlying_graph[target].laneletOrArea.id());
77
78 vertex_and_edges.edge_routing_costs.push_back(underlying_graph[edge].routingCost);
79 vertex_and_edges.edge_routing_cost_source_ids.push_back(underlying_graph[edge].costId);
80
81 uint8_t relation = 0;
82 switch(underlying_graph[edge].relation) {
83 case lanelet::routing::RelationType::Successor:
84 relation = autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges::RELATION_SUCCESSOR; break;
86 relation = autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges::RELATION_LEFT; break;
88 relation = autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges::RELATION_RIGHT; break;
89 case lanelet::routing::RelationType::AdjacentLeft:
90 relation = autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges::RELATION_ADJACENT_LEFT; break;
91 case lanelet::routing::RelationType::AdjacentRight:
92 relation = autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges::RELATION_ADJACENT_RIGHT; break;
93 case lanelet::routing::RelationType::Conflicting:
94 relation = autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges::RELATION_CONFLICTING; break;
95 case lanelet::routing::RelationType::Area:
96 relation = autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges::RELATION_AREA; break;
97 default: // None relation will be default
98 relation = autoware_lanelet2_msgs::msg::RoutingGraphVertexAndEdges::RELATION_NONE; break;
99 }
100
101 vertex_and_edges.edge_relations.push_back(relation);
102
103 }
104
105 vertex_and_edges.lanelet_or_area = underlying_graph[source].laneletOrArea.id();
106
107 // Assign core vertext to the correct array in the ros message based on its type
108 if (underlying_graph[source].laneletOrArea.isLanelet()) { // Lanelet
109 msg.lanelet_vertices.push_back(vertex_and_edges);
110
111 } else { // Area
112 msg.area_vertices.push_back(vertex_and_edges);
113 }
114
115 }
116
117 return msg;
118 }

References sci_strategic_plugin::Left, and sci_strategic_plugin::Right.


The documentation for this class was generated from the following file: