Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
3afff13e
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,体验更适合开发者的 AI 搜索 >>
提交
3afff13e
编写于
9月 13, 2018
作者:
J
Jiangtao Hu
提交者:
Qi Luo
9月 13, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
control: migrate control_tester tool to cybertron.
上级
75c0d3f5
变更
2
隐藏空白更改
内联
并排
Showing
2 changed file
with
81 addition
and
36 deletion
+81
-36
modules/control/tools/BUILD
modules/control/tools/BUILD
+15
-12
modules/control/tools/control_tester.cc
modules/control/tools/control_tester.cc
+66
-24
未找到文件。
modules/control/tools/BUILD
浏览文件 @
3afff13e
...
...
@@ -15,17 +15,20 @@ package(default_visibility = ["//visibility:public"])
# ],
#)
#cc_binary(
# name = "control_tester",
# srcs = ["control_tester.cc"],
# deps = [
# "//modules/canbus/proto:canbus_proto",
# "//modules/common:log",
# "//modules/control/common:control_gflags",
# "//modules/localization/proto:localization_proto",
# "//modules/planning/proto:planning_proto",
# "@ros//:ros_common",
# ],
#)
cc_binary
(
name
=
"control_tester"
,
srcs
=
[
"control_tester.cc"
],
deps
=
[
"//framework:cybertron"
,
"//modules/canbus/proto:canbus_proto"
,
"//modules/common:log"
,
"//modules/common/adapters:adapter_gflags"
,
"//modules/common/util"
,
"//modules/control/common:control_gflags"
,
"//modules/control/proto:control_proto"
,
"//modules/localization/proto:localization_proto"
,
"//modules/planning/proto:planning_proto"
,
],
)
cpplint
()
modules/control/tools/control_tester.cc
浏览文件 @
3afff13e
...
...
@@ -18,29 +18,34 @@
#include <thread>
#include "gflags/gflags.h"
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "modules/localization/proto/localization.pb.h"
#include "modules/planning/proto/planning.pb.h"
#include "cybertron/cybertron.h"
#include "cybertron/time/rate.h"
#include "cybertron/time/time.h"
#include "modules/canbus/proto/chassis.pb.h"
#include "modules/common/adapters/adapter_
manager
.h"
#include "modules/common/adapters/adapter_
gflags
.h"
#include "modules/common/log.h"
#include "modules/common/util/file.h"
#include "modules/control/common/control_gflags.h"
#include "modules/control/proto/pad_msg.pb.h"
#include "modules/localization/proto/localization.pb.h"
#include "modules/planning/proto/planning.pb.h"
DEFINE_string
(
chassis_test_file
,
"modules/control/testdata/control_tester/chassis.pb.txt"
,
chassis_test_file
,
"/apollo/modules/control/testdata/control_tester/chassis.pb.txt"
,
"Used for sending simulated Chassis content to the control node."
);
DEFINE_string
(
l10n_test_file
,
"modules/control/testdata/control_tester/localization.pb.txt"
,
"Used for sending simulated localization to the control node."
);
DEFINE_string
(
localization_test_file
,
"/apollo/modules/control/testdata/control_tester/localization.pb.txt"
,
"Used for sending simulated localization to the control node."
);
DEFINE_string
(
pad_msg_test_file
,
"modules/control/testdata/control_tester/pad_msg.pb.txt"
,
"
/apollo/
modules/control/testdata/control_tester/pad_msg.pb.txt"
,
"Used for sending simulated PadMsg content to the control node."
);
DEFINE_string
(
planning_test_file
,
"modules/control/testdata/control_tester/planning.pb.txt"
,
"
/apollo/
modules/control/testdata/control_tester/planning.pb.txt"
,
"Used for sending simulated Planning content to the control node."
);
DEFINE_int32
(
num_seconds
,
10
,
"Length of execution."
);
DEFINE_int32
(
feed_frequency
,
10
,
...
...
@@ -49,25 +54,62 @@ DEFINE_int32(feed_frequency, 10,
int
main
(
int
argc
,
char
**
argv
)
{
using
std
::
this_thread
::
sleep_for
;
using
apollo
::
canbus
::
Chassis
;
using
apollo
::
common
::
adapter
::
AdapterManager
;
using
apollo
::
control
::
PadMessage
;
using
apollo
::
localization
::
LocalizationEstimate
;
using
apollo
::
cybertron
::
Rate
;
using
apollo
::
cybertron
::
Time
;
using
apollo
::
planning
::
ADCTrajectory
;
using
apollo
::
canbus
::
Chassis
;
using
apollo
::
localization
::
LocalizationEstimate
;
using
apollo
::
control
::
PadMessage
;
google
::
InitGoogleLogging
(
argv
[
0
]);
google
::
ParseCommandLineFlags
(
&
argc
,
&
argv
,
true
);
apollo
::
cybertron
::
Init
(
argv
[
0
]);
FLAGS_alsologtostderr
=
true
;
const
std
::
string
&
config_file
=
"modules/control/testdata/control_tester/adapter.conf"
;
ros
::
init
(
argc
,
argv
,
"control_tester"
);
AdapterManager
::
Init
(
config_file
);
AINFO
<<
"AdapterManager is initialized."
;
Chassis
chassis
;
if
(
!
apollo
::
common
::
util
::
GetProtoFromFile
(
FLAGS_chassis_test_file
,
&
chassis
))
{
AERROR
<<
"failed to load file: "
<<
FLAGS_chassis_test_file
;
return
-
1
;
}
LocalizationEstimate
localization
;
if
(
!
apollo
::
common
::
util
::
GetProtoFromFile
(
FLAGS_localization_test_file
,
&
localization
))
{
AERROR
<<
"failed to load file: "
<<
FLAGS_localization_test_file
;
return
-
1
;
}
PadMessage
pad_msg
;
if
(
!
apollo
::
common
::
util
::
GetProtoFromFile
(
FLAGS_pad_msg_test_file
,
&
pad_msg
))
{
AERROR
<<
"failed to load file: "
<<
FLAGS_pad_msg_test_file
;
return
-
1
;
}
ADCTrajectory
trajectory
;
if
(
!
apollo
::
common
::
util
::
GetProtoFromFile
(
FLAGS_planning_test_file
,
&
trajectory
))
{
AERROR
<<
"failed to load file: "
<<
FLAGS_planning_test_file
;
return
-
1
;
}
std
::
shared_ptr
<
apollo
::
cybertron
::
Node
>
node
(
apollo
::
cybertron
::
CreateNode
(
"routing_tester"
));
auto
chassis_writer
=
node
->
CreateWriter
<
Chassis
>
(
FLAGS_chassis_topic
);
auto
localization_writer
=
node
->
CreateWriter
<
LocalizationEstimate
>
(
FLAGS_localization_topic
);
auto
pad_msg_writer
=
node
->
CreateWriter
<
PadMessage
>
(
FLAGS_pad_topic
);
auto
planning_writer
=
node
->
CreateWriter
<
ADCTrajectory
>
(
FLAGS_planning_trajectory_topic
);
for
(
int
i
=
0
;
i
<
FLAGS_num_seconds
*
FLAGS_feed_frequency
;
++
i
)
{
AdapterManager
::
FeedChassisFile
(
FLAGS_chassis_test_file
);
AdapterManager
::
FeedLocalizationFile
(
FLAGS_l10n_test_file
);
AdapterManager
::
FeedPadFile
(
FLAGS_pad_msg_test_file
);
AdapterManager
::
FeedPlanningFile
(
FLAGS_planning_test_file
);
chassis_writer
->
Write
(
chassis
);
localization_writer
->
Write
(
localization
);
pad_msg_writer
->
Write
(
pad_msg
);
planning_writer
->
Write
(
trajectory
);
sleep_for
(
std
::
chrono
::
milliseconds
(
1000
/
FLAGS_feed_frequency
));
}
AINFO
<<
"Successfully fed proto files."
;
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录