Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
3bd0ba6f
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,发现更多精彩内容 >>
提交
3bd0ba6f
编写于
7月 31, 2017
作者:
S
siyangy
提交者:
Jiangtao Hu
8月 01, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
simplify FillHeader
上级
1e1e1aa7
变更
14
隐藏空白更改
内联
并排
Showing
14 changed file
with
51 addition
and
38 deletion
+51
-38
modules/canbus/canbus.cc
modules/canbus/canbus.cc
+1
-1
modules/canbus/tools/teleop.cc
modules/canbus/tools/teleop.cc
+1
-2
modules/common/adapters/adapter.h
modules/common/adapters/adapter.h
+22
-8
modules/common/adapters/adapter_manager.h
modules/common/adapters/adapter_manager.h
+8
-4
modules/common/monitor/monitor.cc
modules/common/monitor/monitor.cc
+1
-1
modules/control/control.cc
modules/control/control.cc
+1
-2
modules/control/tools/terminal.cc
modules/control/tools/terminal.cc
+5
-5
modules/decision/decision.cc
modules/decision/decision.cc
+1
-1
modules/dreamview/backend/sim_control/sim_control.cc
modules/dreamview/backend/sim_control/sim_control.cc
+2
-3
modules/hmi/ros_node/ros_node_service.cc
modules/hmi/ros_node/ros_node_service.cc
+5
-5
modules/localization/camera/camera_localization.cc
modules/localization/camera/camera_localization.cc
+1
-1
modules/localization/rtk/rtk_localization.cc
modules/localization/rtk/rtk_localization.cc
+1
-1
modules/planning/planning.cc
modules/planning/planning.cc
+1
-2
modules/prediction/prediction.cc
modules/prediction/prediction.cc
+1
-2
未找到文件。
modules/canbus/canbus.cc
浏览文件 @
3bd0ba6f
...
...
@@ -141,7 +141,7 @@ Status Canbus::Start() {
void
Canbus
::
PublishChassis
()
{
Chassis
chassis
=
vehicle_controller_
->
chassis
();
AdapterManager
::
FillChassisHeader
(
FLAGS_node_name
,
chassis
.
mutable_header
()
);
AdapterManager
::
FillChassisHeader
(
FLAGS_node_name
,
&
chassis
);
AdapterManager
::
PublishChassis
(
chassis
);
ADEBUG
<<
chassis
.
ShortDebugString
();
...
...
modules/canbus/tools/teleop.cc
浏览文件 @
3bd0ba6f
...
...
@@ -307,8 +307,7 @@ class Teleop {
}
void
Send
()
{
AdapterManager
::
FillControlCommandHeader
(
"control"
,
control_command_
.
mutable_header
());
AdapterManager
::
FillControlCommandHeader
(
"control"
,
&
control_command_
);
AdapterManager
::
PublishControlCommand
(
control_command_
);
ADEBUG
<<
"Control Command send OK:"
<<
control_command_
.
ShortDebugString
();
}
...
...
modules/common/adapters/adapter.h
浏览文件 @
3bd0ba6f
...
...
@@ -114,7 +114,9 @@ class Adapter {
/**
* @brief returns the topic name that this adapter listens to.
*/
const
std
::
string
&
topic_name
()
const
{
return
topic_name_
;
}
const
std
::
string
&
topic_name
()
const
{
return
topic_name_
;
}
/**
* @brief reads the proto message from the file, and push it into
...
...
@@ -132,7 +134,9 @@ class Adapter {
* the adapter.
* @param data the input data.
*/
void
FeedData
(
const
D
&
data
)
{
EnqueueData
(
data
);
}
void
FeedData
(
const
D
&
data
)
{
EnqueueData
(
data
);
}
/**
* @brief the callback that will be invoked whenever a new
...
...
@@ -205,14 +209,18 @@ class Adapter {
* queue. The caller can use it to iterate over the observed data
* from the head. The API also supports range based for loop.
*/
Iterator
begin
()
const
{
return
observed_queue_
.
begin
();
}
Iterator
begin
()
const
{
return
observed_queue_
.
begin
();
}
/**
* @brief returns an iterator representing the tail of the observing
* queue. The caller can use it to iterate over the observed data
* from the head. The API also supports range based for loop.
*/
Iterator
end
()
const
{
return
observed_queue_
.
end
();
}
Iterator
end
()
const
{
return
observed_queue_
.
end
();
}
/**
* @brief registers the provided callback function to the adapter,
...
...
@@ -220,14 +228,18 @@ class Adapter {
* message hits the adapter.
* @param callback the callback with signature void(const D &).
*/
void
SetCallback
(
Callback
callback
)
{
receive_callback_
=
callback
;
}
void
SetCallback
(
Callback
callback
)
{
receive_callback_
=
callback
;
}
/**
* @brief fills the fields module_name, timestamp_sec and
* sequence_num in the header.
*/
void
FillHeader
(
const
std
::
string
&
module_name
,
apollo
::
common
::
Header
*
header
)
{
void
FillHeader
(
const
std
::
string
&
module_name
,
D
*
data
)
{
static_assert
(
std
::
is_base_of
<
google
::
protobuf
::
Message
,
D
>::
value
,
"Can only fill header to proto messages!"
);
auto
*
header
=
data
->
mutable_header
();
double
timestamp
=
apollo
::
common
::
time
::
ToSecond
(
apollo
::
common
::
time
::
Clock
::
Now
());
header
->
set_module_name
(
module_name
);
...
...
@@ -235,7 +247,9 @@ class Adapter {
header
->
set_sequence_num
(
++
seq_num_
);
}
uint32_t
GetSeqNum
()
const
{
return
seq_num_
;
}
uint32_t
GetSeqNum
()
const
{
return
seq_num_
;
}
private:
template
<
typename
T
>
...
...
modules/common/adapters/adapter_manager.h
浏览文件 @
3bd0ba6f
...
...
@@ -71,9 +71,11 @@ namespace adapter {
static void Publish##name(const name##Adapter::DataType &data) { \
instance()->InternalPublish##name(data); \
} \
static void Fill##name##Header(const std::string &module_name, \
apollo::common::Header *header) { \
instance()->name##_->FillHeader(module_name, header); \
template <typename T> \
static void Fill##name##Header(const std::string &module_name, T *data) { \
static_assert(std::is_same<name##Adapter::DataType, T>::value, \
"Data type must be the same with adapter's type!"); \
instance()->name##_->FillHeader(module_name, data); \
} \
static void Set##name##Callback(name##Adapter::Callback callback) { \
CHECK(instance()->name##_) \
...
...
@@ -108,7 +110,9 @@ namespace adapter {
\
observers_.push_back([this]() { name##_->Observe(); }); \
} \
name##Adapter *InternalGet##name() { return name##_.get(); } \
name##Adapter *InternalGet##name() { \
return name##_.get(); \
} \
void InternalPublish##name(const name##Adapter::DataType &data) { \
name##publisher_.publish(data); \
}
...
...
modules/common/monitor/monitor.cc
浏览文件 @
3bd0ba6f
...
...
@@ -44,7 +44,7 @@ void Monitor::Publish(const std::vector<MessageItem> &messages) const {
}
void
Monitor
::
DoPublish
(
MonitorMessage
*
message
)
const
{
AdapterManager
::
FillMonitorHeader
(
"monitor"
,
message
->
mutable_header
()
);
AdapterManager
::
FillMonitorHeader
(
"monitor"
,
message
);
AdapterManager
::
PublishMonitor
(
*
message
);
}
...
...
modules/control/control.cc
浏览文件 @
3bd0ba6f
...
...
@@ -293,8 +293,7 @@ Status Control::CheckTimestamp() {
void
Control
::
SendCmd
(
ControlCommand
*
control_command
)
{
// set header
AdapterManager
::
FillControlCommandHeader
(
Name
(),
control_command
->
mutable_header
());
AdapterManager
::
FillControlCommandHeader
(
Name
(),
control_command
);
ADEBUG
<<
control_command
->
ShortDebugString
();
if
(
FLAGS_is_control_test_mode
)
{
...
...
modules/control/tools/terminal.cc
浏览文件 @
3bd0ba6f
...
...
@@ -50,16 +50,16 @@ void help() {
}
void
send
(
int
cmd_type
)
{
::
apollo
::
control
::
PadMessage
p
b
;
::
apollo
::
control
::
PadMessage
p
ad
;
if
(
cmd_type
==
RESET_COMMAND
)
{
p
b
.
set_action
(
apollo
::
control
::
DrivingAction
::
RESET
);
p
ad
.
set_action
(
apollo
::
control
::
DrivingAction
::
RESET
);
AINFO
<<
"sending reset action command."
;
}
else
if
(
cmd_type
==
AUTO_DRIVE_COMMAND
)
{
p
b
.
set_action
(
apollo
::
control
::
DrivingAction
::
START
);
p
ad
.
set_action
(
apollo
::
control
::
DrivingAction
::
START
);
AINFO
<<
"sending start action command."
;
}
AdapterManager
::
FillPadHeader
(
"terminal"
,
pb
.
mutable_header
()
);
AdapterManager
::
PublishPad
(
p
b
);
AdapterManager
::
FillPadHeader
(
"terminal"
,
&
pad
);
AdapterManager
::
PublishPad
(
p
ad
);
AINFO
<<
"send pad_message OK"
;
}
...
...
modules/decision/decision.cc
浏览文件 @
3bd0ba6f
...
...
@@ -48,7 +48,7 @@ void Decision::OnTimer(const ros::TimerEvent &) { PublishDecision(); }
void
Decision
::
PublishDecision
()
{
DecisionResult
decision_result
;
AdapterManager
::
FillDecisionHeader
(
Name
(),
decision_result
.
mutable_header
()
);
AdapterManager
::
FillDecisionHeader
(
Name
(),
&
decision_result
);
AdapterManager
::
PublishDecision
(
decision_result
);
}
...
...
modules/dreamview/backend/sim_control/sim_control.cc
浏览文件 @
3bd0ba6f
...
...
@@ -172,7 +172,7 @@ void SimControl::TimerCallback(const ros::TimerEvent& event) {
void
SimControl
::
PublishChassis
(
double
lambda
)
{
Chassis
chassis
;
AdapterManager
::
FillChassisHeader
(
"SimControl"
,
chassis
.
mutable_header
()
);
AdapterManager
::
FillChassisHeader
(
"SimControl"
,
&
chassis
);
chassis
.
set_engine_started
(
true
);
chassis
.
set_driving_mode
(
Chassis
::
COMPLETE_AUTO_DRIVE
);
...
...
@@ -188,8 +188,7 @@ void SimControl::PublishChassis(double lambda) {
void
SimControl
::
PublishLocalization
(
double
lambda
)
{
LocalizationEstimate
localization
;
AdapterManager
::
FillLocalizationHeader
(
"SimControl"
,
localization
.
mutable_header
());
AdapterManager
::
FillLocalizationHeader
(
"SimControl"
,
&
localization
);
auto
*
pose
=
localization
.
mutable_pose
();
auto
prev
=
prev_point_
.
path_point
();
...
...
modules/hmi/ros_node/ros_node_service.cc
浏览文件 @
3bd0ba6f
...
...
@@ -47,11 +47,11 @@ namespace {
static
constexpr
char
kHMIRosNodeName
[]
=
"hmi_ros_node_service"
;
void
SendPadMessage
(
DrivingAction
action
)
{
control
::
PadMessage
p
b
;
p
b
.
set_action
(
action
);
AINFO
<<
"Sending PadMessage:
\n
"
<<
p
b
.
DebugString
();
AdapterManager
::
FillPadHeader
(
kHMIRosNodeName
,
pb
.
mutable_header
()
);
AdapterManager
::
PublishPad
(
p
b
);
control
::
PadMessage
p
ad
;
p
ad
.
set_action
(
action
);
AINFO
<<
"Sending PadMessage:
\n
"
<<
p
ad
.
DebugString
();
AdapterManager
::
FillPadHeader
(
kHMIRosNodeName
,
&
pad
);
AdapterManager
::
PublishPad
(
p
ad
);
}
/**
...
...
modules/localization/camera/camera_localization.cc
浏览文件 @
3bd0ba6f
...
...
@@ -142,7 +142,7 @@ bool CameraLocalization::CreateLocalizationMsg(
// header
AdapterManager
::
FillLocalizationHeader
(
FLAGS_localization_module_name
,
localization
->
mutable_header
()
);
localization
);
if
(
FLAGS_enable_gps_timestamp
)
{
// copy time stamp, do NOT use Clock::Now()
localization
->
mutable_header
()
->
set_timestamp_sec
(
...
...
modules/localization/rtk/rtk_localization.cc
浏览文件 @
3bd0ba6f
...
...
@@ -255,7 +255,7 @@ void RTKLocalization::ComposeLocalizationMsg(
// header
AdapterManager
::
FillLocalizationHeader
(
FLAGS_localization_module_name
,
localization
->
mutable_header
()
);
localization
);
if
(
FLAGS_enable_gps_timestamp
)
{
// copy time stamp, do NOT use Clock::Now()
localization
->
mutable_header
()
->
set_timestamp_sec
(
...
...
modules/planning/planning.cc
浏览文件 @
3bd0ba6f
...
...
@@ -245,8 +245,7 @@ void Planning::RunOnce() {
ADEBUG
<<
"Planning latency: "
<<
trajectory_pb
.
latency_stats
().
DebugString
();
if
(
res_planning
)
{
AdapterManager
::
FillPlanningHeader
(
"planning"
,
trajectory_pb
.
mutable_header
());
AdapterManager
::
FillPlanningHeader
(
"planning"
,
&
trajectory_pb
);
trajectory_pb
.
mutable_header
()
->
set_timestamp_sec
(
execution_start_time
);
AdapterManager
::
PublishPlanning
(
trajectory_pb
);
ADEBUG
<<
"Planning succeeded:"
<<
trajectory_pb
.
header
().
DebugString
();
...
...
modules/prediction/prediction.cc
浏览文件 @
3bd0ba6f
...
...
@@ -120,8 +120,7 @@ void Prediction::OnPerception(const PerceptionObstacles &perception_obstacles) {
PredictionObstacles
prediction_obstacles
;
prediction_obstacles
.
CopyFrom
(
PredictorManager
::
instance
()
->
prediction_obstacles
());
AdapterManager
::
FillPredictionHeader
(
Name
(),
prediction_obstacles
.
mutable_header
());
AdapterManager
::
FillPredictionHeader
(
Name
(),
&
prediction_obstacles
);
AdapterManager
::
PublishPrediction
(
prediction_obstacles
);
ADEBUG
<<
"Published a prediction message ["
<<
prediction_obstacles
.
ShortDebugString
()
<<
"]."
;
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录