Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
5e95878b
A
apollo
项目概览
Pinoxchio
/
apollo
与 Fork 源项目一致
从无法访问的项目Fork
通知
2
Star
0
Fork
0
代码
文件
提交
分支
Tags
贡献者
分支图
Diff
Issue
0
列表
看板
标记
里程碑
合并请求
0
Wiki
0
Wiki
分析
仓库
DevOps
项目成员
Pages
A
apollo
项目概览
项目概览
详情
发布
仓库
仓库
文件
提交
分支
标签
贡献者
分支图
比较
Issue
0
Issue
0
列表
看板
标记
里程碑
合并请求
0
合并请求
0
Pages
分析
分析
仓库分析
DevOps
Wiki
0
Wiki
成员
成员
收起侧边栏
关闭侧边栏
动态
分支图
创建新Issue
提交
Issue看板
体验新版 GitCode,发现更多精彩内容 >>
提交
5e95878b
编写于
9月 08, 2017
作者:
H
henryhu6
提交者:
Jiangtao Hu
9月 12, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Routing: convert from gflag to proto config for parameter tuning (in progress)
上级
c5c64df4
变更
11
隐藏空白更改
内联
并排
Showing
11 changed file
with
44 addition
and
9 deletion
+44
-9
modules/routing/common/routing_gflags.cc
modules/routing/common/routing_gflags.cc
+3
-0
modules/routing/common/routing_gflags.h
modules/routing/common/routing_gflags.h
+1
-0
modules/routing/conf/routing.pb.txt
modules/routing/conf/routing.pb.txt
+2
-1
modules/routing/proto/BUILD
modules/routing/proto/BUILD
+1
-0
modules/routing/proto/routing_config.proto
modules/routing/proto/routing_config.proto
+1
-0
modules/routing/routing.cc
modules/routing/routing.cc
+6
-0
modules/routing/routing.h
modules/routing/routing.h
+3
-0
modules/routing/topo_creator/BUILD
modules/routing/topo_creator/BUILD
+3
-2
modules/routing/topo_creator/graph_creator.cc
modules/routing/topo_creator/graph_creator.cc
+5
-4
modules/routing/topo_creator/graph_creator.h
modules/routing/topo_creator/graph_creator.h
+5
-1
modules/routing/topo_creator/topo_creator.cc
modules/routing/topo_creator/topo_creator.cc
+14
-1
未找到文件。
modules/routing/common/routing_gflags.cc
浏览文件 @
5e95878b
...
...
@@ -16,6 +16,9 @@
#include "modules/routing/common/routing_gflags.h"
DEFINE_string
(
routing_conf_file
,
"modules/routing/conf/routing.pb.txt"
,
"default routing conf data file"
);
DEFINE_string
(
node_name
,
"routing"
,
"the name for this node"
);
DEFINE_string
(
node_namespace
,
"routing"
,
"the namespace for this node"
);
...
...
modules/routing/common/routing_gflags.h
浏览文件 @
5e95878b
...
...
@@ -19,6 +19,7 @@
#include "gflags/gflags.h"
DECLARE_string
(
routing_conf_file
);
DECLARE_string
(
node_name
);
DECLARE_string
(
node_namespace
);
...
...
modules/routing/conf/routing.pb.txt
浏览文件 @
5e95878b
...
...
@@ -3,4 +3,5 @@ left_turn_penalty: 50.0
right_turn_penalty: 20.0
uturn_penalty: 100.0
change_penalty: 50.0
base_changing_length: 50.0
\ No newline at end of file
base_changing_length: 50.0
min_length_for_lane_change: 10.0
\ No newline at end of file
modules/routing/proto/BUILD
浏览文件 @
5e95878b
...
...
@@ -11,6 +11,7 @@ proto_library(
name
=
"routing_proto_lib"
,
srcs
=
[
"routing.proto"
,
"routing_config.proto"
,
"topo_graph.proto"
,
],
deps
=
[
...
...
modules/routing/proto/routing_config.proto
浏览文件 @
5e95878b
...
...
@@ -9,4 +9,5 @@ message RoutingConfig {
optional
double
uturn_penalty
=
4
;
// left turn penalty for node creater [m]
optional
double
change_penalty
=
5
;
// change penalty for edge creater [m]
optional
double
base_changing_length
=
6
;
// base change length penalty for edge creater [m]
optional
double
min_length_for_lane_change
=
7
;
// min length for lane change [m]
}
modules/routing/routing.cc
浏览文件 @
5e95878b
...
...
@@ -37,6 +37,12 @@ apollo::common::Status Routing::Init() {
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
));
CHECK
(
::
apollo
::
common
::
util
::
GetProtoFromFile
(
FLAGS_routing_conf_file
,
&
routing_conf_
))
<<
"Unable to load control conf file: "
+
FLAGS_routing_conf_file
;
AINFO
<<
"Conf file: "
<<
FLAGS_routing_conf_file
<<
" is loaded."
;
AdapterManager
::
Init
(
FLAGS_adapter_config_filename
);
AdapterManager
::
AddRoutingRequestCallback
(
&
Routing
::
OnRouting_Request
,
this
);
return
apollo
::
common
::
Status
::
OK
();
...
...
modules/routing/routing.h
浏览文件 @
5e95878b
...
...
@@ -21,6 +21,7 @@
#include <string>
#include "modules/routing/proto/routing.pb.h"
#include "modules/routing/proto/routing_config.pb.h"
#include "modules/common/apollo_app.h"
#include "modules/common/monitor/monitor.h"
...
...
@@ -68,6 +69,8 @@ class Routing : public apollo::common::ApolloApp {
private:
std
::
unique_ptr
<
Navigator
>
navigator_ptr_
;
apollo
::
common
::
monitor
::
Monitor
monitor_
;
RoutingConfig
routing_conf_
;
};
}
// namespace routing
...
...
modules/routing/topo_creator/BUILD
浏览文件 @
5e95878b
...
...
@@ -30,12 +30,10 @@ cc_library(
deps
=
[
":edge_creator"
,
":node_creator"
,
"//external:gflags"
,
"//modules/common"
,
"//modules/common/util"
,
"//modules/map/hdmap/adapter:opendrive_adapter"
,
"//modules/map/proto:map_proto"
,
"//modules/routing/common:routing_gflags"
,
"//modules/routing/proto:routing_proto"
,
],
)
...
...
@@ -65,7 +63,10 @@ cc_binary(
"//external:gflags"
,
"//modules/common"
,
"//modules/common:log"
,
"//modules/common:apollo_app"
,
"//modules/common/configs:config_gflags"
,
"//modules/common/status"
,
"//modules/common/util"
,
"//modules/map/hdmap:hdmap_util"
,
"//modules/map/proto:map_proto"
,
"//modules/routing/common:routing_gflags"
,
...
...
modules/routing/topo_creator/graph_creator.cc
浏览文件 @
5e95878b
...
...
@@ -19,7 +19,6 @@
#include "glog/logging.h"
#include "modules/common/util/file.h"
#include "modules/routing/common/routing_gflags.h"
#include "modules/map/hdmap/adapter/opendrive_adapter.h"
#include "modules/routing/topo_creator/edge_creator.h"
#include "modules/routing/topo_creator/node_creator.h"
...
...
@@ -49,9 +48,11 @@ bool IsAllowedToCross(const LaneBoundary& boundary) {
}
// namespace
GraphCreator
::
GraphCreator
(
const
std
::
string
&
base_map_file_path
,
const
std
::
string
&
dump_topo_file_path
)
const
std
::
string
&
dump_topo_file_path
,
const
RoutingConfig
*
routing_conf
)
:
base_map_file_path_
(
base_map_file_path
),
dump_topo_file_path_
(
dump_topo_file_path
)
{}
dump_topo_file_path_
(
dump_topo_file_path
),
routing_conf_
(
routing_conf
)
{}
bool
GraphCreator
::
Create
()
{
if
(
common
::
util
::
EndWith
(
base_map_file_path_
,
".xml"
))
{
...
...
@@ -115,7 +116,7 @@ bool GraphCreator::Create() {
const
auto
&
from_node
=
graph_
.
node
(
node_index_map_
[
lane_id
]);
AddEdge
(
from_node
,
lane
.
successor_id
(),
Edge
::
FORWARD
);
if
(
lane
.
length
()
<
FLAGS_min_length_for_lane_change
)
{
if
(
lane
.
length
()
<
routing_conf_
->
min_length_for_lane_change
()
)
{
continue
;
}
if
(
lane
.
has_left_boundary
()
&&
IsAllowedToCross
(
lane
.
left_boundary
()))
{
...
...
modules/routing/topo_creator/graph_creator.h
浏览文件 @
5e95878b
...
...
@@ -23,6 +23,7 @@
#include "modules/map/proto/map.pb.h"
#include "modules/routing/proto/topo_graph.pb.h"
#include "modules/routing/proto/routing_config.pb.h"
namespace
apollo
{
namespace
routing
{
...
...
@@ -30,7 +31,8 @@ namespace routing {
class
GraphCreator
{
public:
GraphCreator
(
const
std
::
string
&
base_map_file_path
,
const
std
::
string
&
dump_topo_file_path
);
const
std
::
string
&
dump_topo_file_path
,
const
RoutingConfig
*
routing_conf
);
~
GraphCreator
()
=
default
;
...
...
@@ -54,6 +56,8 @@ class GraphCreator {
std
::
unordered_map
<
std
::
string
,
std
::
string
>
road_id_map_
;
std
::
unordered_set
<
std
::
string
>
showed_edge_id_set_
;
std
::
unordered_set
<
std
::
string
>
forbidden_lane_id_set_
;
const
RoutingConfig
*
routing_conf_
=
nullptr
;
};
}
// namespace routing
...
...
modules/routing/topo_creator/topo_creator.cc
浏览文件 @
5e95878b
...
...
@@ -18,14 +18,27 @@
#include "modules/common/log.h"
#include "modules/map/hdmap/hdmap_util.h"
#include "modules/routing/topo_creator/graph_creator.h"
#include "modules/routing/proto/routing_config.pb.h"
#include "modules/common/apollo_app.h"
#include "modules/common/util/file.h"
#include "modules/routing/common/routing_gflags.h"
int
main
(
int
argc
,
char
**
argv
)
{
google
::
InitGoogleLogging
(
argv
[
0
]);
google
::
ParseCommandLineFlags
(
&
argc
,
&
argv
,
true
);
apollo
::
routing
::
RoutingConfig
routing_conf
;
CHECK
(
apollo
::
common
::
util
::
GetProtoFromFile
(
FLAGS_routing_conf_file
,
&
routing_conf
))
<<
"Unable to load control conf file: "
+
FLAGS_routing_conf_file
;
AINFO
<<
"Conf file: "
<<
FLAGS_routing_conf_file
<<
" is loaded."
;
const
auto
base_map
=
apollo
::
hdmap
::
BaseMapFile
();
const
auto
routing_map
=
apollo
::
hdmap
::
RoutingMapFile
();
apollo
::
routing
::
GraphCreator
creator
(
base_map
,
routing_map
);
apollo
::
routing
::
GraphCreator
creator
(
base_map
,
routing_map
,
&
routing_conf
);
CHECK
(
creator
.
Create
())
<<
"Create routing topo failed!"
;
AINFO
<<
"Create routing topo successfully from "
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录