Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
9bde4716
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,发现更多精彩内容 >>
提交
9bde4716
编写于
9月 20, 2018
作者:
D
Dong Li
提交者:
Jiangtao Hu
9月 20, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
migrate cybertron drive_event
上级
fab8e62a
变更
1
显示空白变更内容
内联
并排
Showing
1 changed file
with
11 addition
and
15 deletion
+11
-15
modules/tools/rosbag/drive_event.py
modules/tools/rosbag/drive_event.py
+11
-15
未找到文件。
modules/tools/rosbag/drive_event.py
浏览文件 @
9bde4716
...
...
@@ -19,18 +19,15 @@
This program can publish drive event message
"""
import
rosbag
import
std_msgs
from
cybertron
import
cybertron
import
argparse
import
datetime
import
shutil
import
time
import
os
import
rospy
import
sys
from
std_msgs.msg
import
String
from
common.message_manager
import
PbMessageManager
from
common
import
proto_utils
...
...
@@ -79,17 +76,15 @@ if __name__ == "__main__":
g_args
.
localization_topic
)
sys
.
exit
(
0
)
rospy
.
init_node
(
'drive_event_node'
,
anonymous
=
True
)
rospy
.
Subscrib
er
(
localization_meta_msg
.
topic
(),
cybertron
.
init
(
)
node
=
cybertron
.
Node
(
"derive_event_node"
)
node
.
create_read
er
(
localization_meta_msg
.
topic
(),
localization_meta_msg
.
msg_type
(),
OnReceiveLocalization
)
pub
=
rospy
.
Publisher
(
drive_event_meta_msg
.
topic
(),
drive_event_meta_msg
.
msg_type
(),
queue_size
=
10
)
writer
=
node
.
create_writer
(
drive_event_meta_msg
.
topic
(),
drive_event_meta_msg
.
msg_type
())
seq_num
=
0
while
not
rospy
.
is_shutdown
():
while
not
cybertron
.
is_shutdown
():
event_type
=
raw_input
(
"Type in Event Type('d') and press Enter (current time: "
+
str
(
datetime
.
datetime
.
now
())
+
")
\n
>"
)
...
...
@@ -112,9 +107,10 @@ if __name__ == "__main__":
event_msg
.
event
=
event_str
if
g_localization
:
event_msg
.
location
.
CopyFrom
(
g_localization
.
pose
)
pub
.
publish
(
event_msg
)
writer
.
write
(
event_msg
)
time_str
=
datetime
.
datetime
.
fromtimestamp
(
current_time
).
strftime
(
"%Y%m%d%H%M%S"
)
filename
=
os
.
path
.
join
(
g_args
.
dir
,
"%s_drive_event.pb.txt"
%
time_str
)
proto_utils
.
write_pb_to_text_file
(
event_msg
,
filename
)
print
(
"logged to rosbag and written to file %s"
%
filename
)
time
.
sleep
(
0.1
)
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录