Apollo 10.0
自动驾驶开放平台
apollo::routing::Routing类 参考

#include <routing.h>

apollo::routing::Routing 的协作图:

Public 成员函数

 Routing ()
 
std::string Name () const
 module name
 
apollo::common::Status Init ()
 module initialization function
 
apollo::common::Status Start ()
 module start function
 
virtual ~Routing ()=default
 destructor
 
bool Process (const std::shared_ptr< routing::RoutingRequest > &routing_request, routing::RoutingResponse *const routing_response)
 

详细描述

在文件 routing.h33 行定义.

构造及析构函数说明

◆ Routing()

apollo::routing::Routing::Routing ( )

◆ ~Routing()

virtual apollo::routing::Routing::~Routing ( )
virtualdefault

destructor

成员函数说明

◆ Init()

apollo::common::Status apollo::routing::Routing::Init ( )

module initialization function

返回
initialization status

在文件 routing.cc37 行定义.

37 {
38 const auto routing_map_file = apollo::hdmap::RoutingMapFile();
39 AINFO << "Use routing topology graph path: " << routing_map_file;
40 navigator_ptr_.reset(new Navigator(routing_map_file));
41
43 ACHECK(hdmap_) << "Failed to load map file:" << apollo::hdmap::BaseMapFile();
44
46}
static Status OK()
generate a success status.
Definition status.h:60
static const HDMap * BaseMapPtr()
#define ACHECK(cond)
Definition log.h:80
#define AINFO
Definition log.h:42
std::string RoutingMapFile()
get routing map file path from flags.
Definition hdmap_util.cc:63
std::string BaseMapFile()
get base map file path from flags.
Definition hdmap_util.cc:47

◆ Name()

std::string apollo::routing::Routing::Name ( ) const

module name

在文件 routing.cc32 行定义.

32{ return FLAGS_routing_node_name; }

◆ Process()

bool apollo::routing::Routing::Process ( const std::shared_ptr< routing::RoutingRequest > &  routing_request,
routing::RoutingResponse *const  routing_response 
)

在文件 routing.cc129 行定义.

131 {
132 if (nullptr == routing_request) {
133 AWARN << "Routing request is empty!";
134 return true;
135 }
136 CHECK_NOTNULL(routing_response);
137 AINFO << "Get new routing request:" << routing_request->DebugString();
138
139 const auto& fixed_requests = FillLaneInfoIfMissing(*routing_request);
140 double min_routing_length = std::numeric_limits<double>::max();
141 for (const auto& fixed_request : fixed_requests) {
142 routing::RoutingResponse routing_response_temp;
143 if (navigator_ptr_->SearchRoute(fixed_request, &routing_response_temp)) {
144 const double routing_length =
145 routing_response_temp.measurement().distance();
146 if (routing_length < min_routing_length) {
147 routing_response->CopyFrom(routing_response_temp);
148 min_routing_length = routing_length;
149 }
150 }
151 }
152 if (min_routing_length < std::numeric_limits<double>::max()) {
153 monitor_logger_buffer_.INFO("Routing success!");
154 return true;
155 }
156
157 AERROR << "Failed to search route with navigator.";
158 monitor_logger_buffer_.WARN("Routing failed! " +
159 routing_response->status().msg());
160 return false;
161}
#define AERROR
Definition log.h:44
#define AWARN
Definition log.h:43

◆ Start()

apollo::common::Status apollo::routing::Routing::Start ( )

module start function

返回
start status

在文件 routing.cc48 行定义.

48 {
49 if (!navigator_ptr_->IsReady()) {
50 AERROR << "Navigator is not ready!";
51 return apollo::common::Status(ErrorCode::ROUTING_ERROR,
52 "Navigator not ready");
53 }
54 AINFO << "Routing service is ready.";
55 monitor_logger_buffer_.INFO("Routing started");
57}
A general class to denote the return status of an API call.
Definition status.h:43

该类的文档由以下文件生成: