Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
800a614a
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,发现更多精彩内容 >>
提交
800a614a
编写于
9月 01, 2017
作者:
J
Jiangtao Hu
提交者:
Yifei Jiang
9月 01, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
planning: add replay by sequence number.
上级
bd8e29b8
变更
1
隐藏空白更改
内联
并排
Showing
1 changed file
with
51 addition
and
7 deletion
+51
-7
modules/tools/replay/replay_file.py
modules/tools/replay/replay_file.py
+51
-7
未找到文件。
modules/tools/replay/replay_file.py
浏览文件 @
800a614a
...
...
@@ -18,7 +18,7 @@
"""
This program can replay a planning output pb file via ros
"""
import
os.path
import
sys
import
argparse
import
rospy
...
...
@@ -33,13 +33,12 @@ from modules.planning.proto import planning_pb2
from
modules.prediction.proto
import
prediction_obstacle_pb2
from
modules.routing.proto
import
routing_pb2
def
generate_message
(
topic
,
filename
):
"""generate message from file"""
message
=
None
if
topic
==
"/apollo/planning"
:
message
=
planning_pb2
.
ADCTrajectory
()
elif
topic
==
"/apollo/localizatin/pose"
:
elif
topic
==
"/apollo/localizati
o
n/pose"
:
message
=
localization_pb2
.
LocalizationEstimate
()
elif
topic
==
"/apollo/perception/obstacles"
:
message
=
perception_obstacle_pb2
.
PerceptionObstacles
()
...
...
@@ -48,8 +47,10 @@ def generate_message(topic, filename):
elif
topic
==
"/apollo/routing_response"
:
message
=
routing_pb2
.
RoutingResponse
()
if
not
message
:
print
"Unknown topic
: "
<<
topic
<<
", you can add it here"
print
"Unknown topic
:"
,
topic
sys
.
exit
(
0
)
if
not
os
.
path
.
exists
(
filename
):
return
None
f_handle
=
file
(
filename
,
'r'
)
text_format
.
Merge
(
f_handle
.
read
(),
message
)
f_handle
.
close
()
...
...
@@ -66,12 +67,45 @@ def topic_publisher(topic, filename, period):
pub
.
publish
(
str
(
message
))
rate
.
sleep
()
def
seq_publisher
(
seq_num
,
period
):
"""publisher"""
rospy
.
init_node
(
'replay_node'
,
anonymous
=
True
)
# topic_name => module_name, pb type, pb, publish_handler
topic_name_map
=
{
"/apollo/localization/pose"
:
[
"localization"
,
localization_pb2
.
LocalizationEstimate
,
None
,
None
],
"/apollo/routing_response"
:
[
"routing"
,
routing_pb2
.
RoutingResponse
,
None
,
None
],
"/apollo/perception/obstacles"
:
[
"perception"
,
perception_obstacle_pb2
.
PerceptionObstacles
,
None
,
None
],
"/apollo/prediction"
:
[
"prediction"
,
prediction_obstacle_pb2
.
PredictionObstacles
,
None
,
None
],
"/apollo/planning"
:
[
"planning"
,
planning_pb2
.
ADCTrajectory
,
None
,
None
],
}
for
topic
,
module_features
in
topic_name_map
.
iteritems
():
filename
=
str
(
seq_num
)
+
"_"
+
module_features
[
0
]
+
".pb.txt"
print
"trying to load pb file:"
,
filename
module_features
[
3
]
=
rospy
.
Publisher
(
topic
,
module_features
[
1
],
queue_size
=
1
)
module_features
[
2
]
=
generate_message
(
topic
,
filename
)
if
module_features
[
2
]
is
None
:
print
topic
,
" pb is none"
rate
=
rospy
.
Rate
(
int
(
1.0
/
period
))
# 10hz
while
not
rospy
.
is_shutdown
():
for
topic
,
module_features
in
topic_name_map
.
iteritems
():
if
not
module_features
[
2
]
is
None
:
module_features
[
3
].
publish
(
module_features
[
2
])
rate
.
sleep
()
if
__name__
==
'__main__'
:
parser
=
argparse
.
ArgumentParser
(
description
=
"replay a planning result pb file"
)
parser
.
add_argument
(
"filename"
,
action
=
"store"
,
type
=
str
,
help
=
"planning result files"
)
"
--
filename"
,
action
=
"store"
,
type
=
str
,
help
=
"planning result files"
)
parser
.
add_argument
(
"--topic"
,
action
=
"store"
,
...
...
@@ -82,10 +116,20 @@ if __name__ == '__main__':
"--period"
,
action
=
"store"
,
type
=
float
,
default
=
0.
1
,
default
=
1
,
help
=
"set the topic publish time duration"
)
parser
.
add_argument
(
"--seq"
,
action
=
"store"
,
type
=
int
,
default
=-
1
,
help
=
"set sequence number to replay"
)
args
=
parser
.
parse_args
()
try
:
topic_publisher
(
args
.
topic
,
args
.
filename
,
args
.
period
)
if
(
args
.
seq
>
0
):
seq_publisher
(
args
.
seq
,
args
.
period
)
else
:
topic_publisher
(
args
.
topic
,
args
.
filename
,
args
.
period
)
except
rospy
.
ROSInterruptException
:
print
"failed to replay message"
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录