Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
e665aad4
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,发现更多精彩内容 >>
提交
e665aad4
编写于
12月 04, 2017
作者:
J
Jiangtao Hu
提交者:
Liangliang Zhang
12月 04, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
perception: add sequence num in traffic light detection msg.
上级
cf7d0178
变更
2
隐藏空白更改
内联
并排
Showing
2 changed file
with
15 addition
and
8 deletion
+15
-8
modules/perception/traffic_light/onboard/proc_subnode.cc
modules/perception/traffic_light/onboard/proc_subnode.cc
+13
-7
modules/perception/traffic_light/onboard/proc_subnode.h
modules/perception/traffic_light/onboard/proc_subnode.h
+2
-1
未找到文件。
modules/perception/traffic_light/onboard/proc_subnode.cc
浏览文件 @
e665aad4
...
...
@@ -199,7 +199,7 @@ bool TLProcSubnode::ProcEvent(const Event &event) {
image_lights
->
preprocess_receive_timestamp
)
*
1000
<<
" ms."
;
// }
return
true
;
}
...
...
@@ -384,7 +384,7 @@ void TLProcSubnode::ComputeRectsOffset(const cv::Rect &rect1,
}
bool
TLProcSubnode
::
PublishMessage
(
const
std
::
shared_ptr
<
ImageLights
>
&
image_lights
)
const
{
const
std
::
shared_ptr
<
ImageLights
>
&
image_lights
)
{
Timer
timer
;
timer
.
Start
();
const
auto
&
lights
=
image_lights
->
lights
;
...
...
@@ -392,6 +392,7 @@ bool TLProcSubnode::PublishMessage(
apollo
::
perception
::
TrafficLightDetection
result
;
apollo
::
common
::
Header
*
header
=
result
.
mutable_header
();
header
->
set_timestamp_sec
(
ros
::
Time
::
now
().
toSec
());
header
->
set_sequence_num
(
seq_num_
++
);
uint64_t
timestamp
=
TimestampDouble2Int64
(
image_lights
->
image
->
ts
());
timestamp
+=
kCameraIndicator
[
image_lights
->
image
->
camera_id
()];
...
...
@@ -481,15 +482,20 @@ bool TLProcSubnode::PublishMessage(
cv
::
Rect
rect
=
lights
->
at
(
i
)
->
region
.
rectified_roi
;
cv
::
Scalar
color
;
switch
(
lights
->
at
(
i
)
->
status
.
color
)
{
case
BLACK
:
color
=
cv
::
Scalar
(
0
,
0
,
0
);
case
BLACK
:
color
=
cv
::
Scalar
(
0
,
0
,
0
);
break
;
case
GREEN
:
color
=
cv
::
Scalar
(
0
,
255
,
0
);
case
GREEN
:
color
=
cv
::
Scalar
(
0
,
255
,
0
);
break
;
case
RED
:
color
=
cv
::
Scalar
(
0
,
0
,
255
);
case
RED
:
color
=
cv
::
Scalar
(
0
,
0
,
255
);
break
;
case
YELLOW
:
color
=
cv
::
Scalar
(
0
,
255
,
255
);
case
YELLOW
:
color
=
cv
::
Scalar
(
0
,
255
,
255
);
break
;
default:
color
=
cv
::
Scalar
(
0
,
76
,
153
);
default:
color
=
cv
::
Scalar
(
0
,
76
,
153
);
}
cv
::
rectangle
(
img
,
rect
,
color
,
2
);
...
...
modules/perception/traffic_light/onboard/proc_subnode.h
浏览文件 @
e665aad4
...
...
@@ -72,7 +72,7 @@ class TLProcSubnode : public Subnode {
// @brief compute offset between two rectangles
void
ComputeRectsOffset
(
const
cv
::
Rect
&
rect1
,
const
cv
::
Rect
&
rect2
,
int
*
offset
);
bool
PublishMessage
(
const
std
::
shared_ptr
<
ImageLights
>
&
image_lights
)
const
;
bool
PublishMessage
(
const
std
::
shared_ptr
<
ImageLights
>
&
image_lights
);
private:
int
image_border_
=
100
;
...
...
@@ -81,6 +81,7 @@ class TLProcSubnode : public Subnode {
std
::
unique_ptr
<
BaseRectifier
>
rectifier_
=
nullptr
;
std
::
unique_ptr
<
BaseRecognizer
>
recognizer_
=
nullptr
;
std
::
unique_ptr
<
BaseReviser
>
reviser_
=
nullptr
;
uint32_t
seq_num_
=
0
;
Mutex
mutex_
;
DISALLOW_COPY_AND_ASSIGN
(
TLProcSubnode
);
};
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录