Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
1ba2e85f
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,发现更多精彩内容 >>
提交
1ba2e85f
编写于
9月 19, 2018
作者:
Y
Yifei Jiang
提交者:
Liangliang Zhang
9月 19, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
planning: added more items in local view. (#313)
上级
470ad547
变更
5
显示空白变更内容
内联
并排
Showing
5 changed file
with
31 addition
and
17 deletion
+31
-17
modules/planning/BUILD
modules/planning/BUILD
+5
-4
modules/planning/common/BUILD
modules/planning/common/BUILD
+12
-11
modules/planning/common/local_view.h
modules/planning/common/local_view.h
+2
-0
modules/planning/planning_component.cc
modules/planning/planning_component.cc
+10
-2
modules/planning/planning_component.h
modules/planning/planning_component.h
+2
-0
未找到文件。
modules/planning/BUILD
浏览文件 @
1ba2e85f
...
...
@@ -17,6 +17,7 @@ cc_library(
"//modules/common/adapters:adapter_gflags"
,
"//modules/common/util:message_util"
,
"//modules/localization/proto:localization_proto"
,
"//modules/map/relative_map/proto:navigation_proto"
,
"//modules/perception/proto:perception_proto"
,
"//modules/planning/proto:planning_proto"
,
"//modules/prediction/proto:prediction_proto"
,
...
...
@@ -34,8 +35,8 @@ cc_test(
"//modules/planning:planning_testdata"
,
],
deps
=
[
":planning_component_lib"
,
"@gtest//:main"
,
":planning_component_lib"
,
],
)
...
...
modules/planning/common/BUILD
浏览文件 @
1ba2e85f
...
...
@@ -22,9 +22,9 @@ cc_test(
"indexed_list_test.cc"
,
],
deps
=
[
"@gtest//:main"
,
":indexed_list"
,
"//modules/common/util"
,
"@gtest//:main"
,
],
)
...
...
@@ -45,9 +45,9 @@ cc_test(
"indexed_queue_test.cc"
,
],
deps
=
[
"@gtest//:main"
,
":indexed_queue"
,
"//modules/common/util"
,
"@gtest//:main"
,
],
)
...
...
@@ -88,10 +88,10 @@ cc_test(
"//modules/planning/common:common_testdata"
,
],
deps
=
[
"@gtest//:main"
,
":obstacle"
,
"//modules/common/util"
,
"//modules/perception/proto:perception_proto"
,
"@gtest//:main"
,
],
)
...
...
@@ -121,8 +121,8 @@ cc_test(
"path_obstacle_test.cc"
,
],
deps
=
[
":path_obstacle"
,
"@gtest//:main"
,
":path_obstacle"
,
],
)
...
...
@@ -179,6 +179,7 @@ cc_library(
"reference_line_info.h"
,
],
deps
=
[
"@eigen"
,
":ego_info"
,
":path_decision"
,
":planning_gflags"
,
...
...
@@ -193,7 +194,6 @@ cc_library(
"//modules/planning/common/trajectory:publishable_trajectory"
,
"//modules/planning/proto:lattice_structure_proto"
,
"//modules/planning/reference_line"
,
"@eigen"
,
],
)
...
...
@@ -204,8 +204,8 @@ cc_test(
"reference_line_info_test.cc"
,
],
deps
=
[
":reference_line_info"
,
"@gtest//:main"
,
":reference_line_info"
,
],
)
...
...
@@ -237,8 +237,8 @@ cc_test(
"speed_profile_generator_test.cc"
,
],
deps
=
[
":speed_profile_generator"
,
"@gtest//:main"
,
":speed_profile_generator"
,
],
)
...
...
@@ -280,6 +280,7 @@ cc_library(
],
deps
=
[
"//modules/localization/proto:localization_proto"
,
"//modules/map/relative_map/proto:navigation_proto"
,
"//modules/perception/proto:perception_proto"
,
"//modules/planning/proto:planning_proto"
,
"//modules/prediction/proto:prediction_proto"
,
...
...
@@ -353,11 +354,11 @@ cc_test(
"//modules/planning/common:common_testdata"
,
],
deps
=
[
"@gtest//:main"
,
":frame"
,
"//modules/common/util"
,
"//modules/map/hdmap:hdmap_util"
,
"//modules/planning/proto:planning_config_proto"
,
"@gtest//:main"
,
],
)
...
...
@@ -402,8 +403,8 @@ cc_test(
"speed_limit_test.cc"
,
],
deps
=
[
":speed_limit"
,
"@gtest//:main"
,
":speed_limit"
,
],
)
...
...
@@ -416,6 +417,7 @@ cc_library(
"ego_info.h"
,
],
deps
=
[
"@eigen"
,
":obstacle"
,
"//framework:cybertron"
,
"//modules/common/configs:vehicle_config_helper"
,
...
...
@@ -423,7 +425,6 @@ cc_library(
"//modules/common/math:geometry"
,
"//modules/common/vehicle_state/proto:vehicle_state_proto"
,
"//modules/planning/reference_line"
,
"@eigen"
,
],
)
...
...
@@ -434,9 +435,9 @@ cc_test(
"ego_info_test.cc"
,
],
deps
=
[
"@gtest//:main"
,
":ego_info"
,
":frame"
,
"@gtest//:main"
,
],
)
...
...
modules/planning/common/local_view.h
浏览文件 @
1ba2e85f
...
...
@@ -24,6 +24,7 @@
#include "modules/perception/proto/traffic_light_detection.pb.h"
#include "modules/prediction/proto/prediction_obstacle.pb.h"
#include "modules/routing/proto/routing.pb.h"
#include "modules/map/relative_map/proto/navigation.pb.h"
namespace
apollo
{
namespace
planning
{
...
...
@@ -39,6 +40,7 @@ struct LocalView {
std
::
shared_ptr
<
localization
::
LocalizationEstimate
>
localization_estimate
;
std
::
shared_ptr
<
perception
::
TrafficLightDetection
>
traffic_light
;
std
::
shared_ptr
<
routing
::
RoutingResponse
>
routing
;
std
::
shared_ptr
<
relative_map
::
MapMsg
>
relative_map
;
};
}
// namespace planning
...
...
modules/planning/planning_component.cc
浏览文件 @
1ba2e85f
...
...
@@ -27,6 +27,7 @@ namespace planning {
using
apollo
::
perception
::
TrafficLightDetection
;
using
apollo
::
routing
::
RoutingResponse
;
using
apollo
::
routing
::
RoutingRequest
;
using
apollo
::
relative_map
::
MapMsg
;
using
apollo
::
hdmap
::
HDMapUtil
;
bool
PlanningComponent
::
Init
()
{
...
...
@@ -54,17 +55,24 @@ bool PlanningComponent::Init() {
pad_message_reader_
=
node_
->
CreateReader
<
PadMessage
>
(
FLAGS_planning_pad_topic
,
[
this
](
const
std
::
shared_ptr
<
PadMessage
>&
pad_message
)
{
ADEBUG
<<
"Received
chassis data: run chassis
callback."
;
ADEBUG
<<
"Received
pad data: run pad
callback."
;
std
::
lock_guard
<
std
::
mutex
>
lock
(
mutex_
);
pad_message_
.
CopyFrom
(
*
pad_message
);
});
relative_map_reader_
=
node_
->
CreateReader
<
MapMsg
>
(
FLAGS_planning_pad_topic
,
[
this
](
const
std
::
shared_ptr
<
MapMsg
>&
map_message
)
{
ADEBUG
<<
"Received relative map data: run relative map callback."
;
std
::
lock_guard
<
std
::
mutex
>
lock
(
mutex_
);
relative_map_
.
CopyFrom
(
*
map_message
);
});
}
planning_writer_
=
node_
->
CreateWriter
<
ADCTrajectory
>
(
FLAGS_planning_trajectory_topic
);
rerouting_writer_
=
node_
->
CreateWriter
<
RoutingRequest
>
(
"/apollo/routing/routing_request"
);
node_
->
CreateWriter
<
RoutingRequest
>
(
FLAGS_routing_request_topic
);
return
true
;
}
...
...
modules/planning/planning_component.h
浏览文件 @
1ba2e85f
...
...
@@ -66,6 +66,7 @@ class PlanningComponent final
traffic_light_reader_
;
std
::
shared_ptr
<
cybertron
::
Reader
<
routing
::
RoutingResponse
>>
routing_reader_
;
std
::
shared_ptr
<
cybertron
::
Reader
<
planning
::
PadMessage
>>
pad_message_reader_
;
std
::
shared_ptr
<
cybertron
::
Reader
<
relative_map
::
MapMsg
>>
relative_map_reader_
;
std
::
shared_ptr
<
cybertron
::
Writer
<
ADCTrajectory
>>
planning_writer_
;
std
::
shared_ptr
<
cybertron
::
Writer
<
routing
::
RoutingRequest
>>
rerouting_writer_
;
...
...
@@ -74,6 +75,7 @@ class PlanningComponent final
perception
::
TrafficLightDetection
traffic_light_
;
routing
::
RoutingResponse
routing_
;
PadMessage
pad_message_
;
relative_map
::
MapMsg
relative_map_
;
LocalView
local_view_
;
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录