Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
ee85a3a9
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,发现更多精彩内容 >>
提交
ee85a3a9
编写于
3月 19, 2018
作者:
J
Jiangtao Hu
提交者:
Jiangtao Hu
3月 20, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
perception: only show short camera in camera visualizer.
上级
4b8b9ada
变更
1
隐藏空白更改
内联
并排
Showing
1 changed file
with
1 addition
and
7 deletion
+1
-7
modules/perception/obstacle/camera/visualizer/camera_visualizer.cc
...erception/obstacle/camera/visualizer/camera_visualizer.cc
+1
-7
未找到文件。
modules/perception/obstacle/camera/visualizer/camera_visualizer.cc
浏览文件 @
ee85a3a9
...
@@ -35,11 +35,10 @@ std::map<std::string, cv::Scalar> kColorTable = {
...
@@ -35,11 +35,10 @@ std::map<std::string, cv::Scalar> kColorTable = {
{
std
::
string
(
"debug_roi"
),
cv
::
Scalar
(
255
,
169
,
255
)}};
{
std
::
string
(
"debug_roi"
),
cv
::
Scalar
(
255
,
169
,
255
)}};
std
::
vector
<
std
::
shared_ptr
<
Image
>>
g_cached_images
;
std
::
vector
<
std
::
shared_ptr
<
Image
>>
g_cached_images
;
const
int
kMaxCachedImageNum
=
10
0
;
const
int
kMaxCachedImageNum
=
10
;
void
OnPerception
(
const
PerceptionObstacles
&
);
void
OnPerception
(
const
PerceptionObstacles
&
);
void
OnImageShort
(
const
sensor_msgs
::
ImagePtr
&
);
void
OnImageShort
(
const
sensor_msgs
::
ImagePtr
&
);
void
OnImageLong
(
const
sensor_msgs
::
ImagePtr
&
);
int
main
(
int
argc
,
char
**
argv
)
{
int
main
(
int
argc
,
char
**
argv
)
{
ros
::
init
(
argc
,
argv
,
"camera_visualizer"
);
ros
::
init
(
argc
,
argv
,
"camera_visualizer"
);
...
@@ -47,8 +46,6 @@ int main(int argc, char **argv) {
...
@@ -47,8 +46,6 @@ int main(int argc, char **argv) {
ros
::
Subscriber
sub_perception_debug
=
ros
::
Subscriber
sub_perception_debug
=
n
.
subscribe
(
FLAGS_perception_obstacle_topic
,
1000
,
OnPerception
);
n
.
subscribe
(
FLAGS_perception_obstacle_topic
,
1000
,
OnPerception
);
ros
::
Subscriber
sub_tl_image_long
=
n
.
subscribe
(
FLAGS_image_long_topic
,
1000
,
OnImageLong
);
ros
::
Subscriber
sub_tl_image_short
=
ros
::
Subscriber
sub_tl_image_short
=
n
.
subscribe
(
FLAGS_image_short_topic
,
1000
,
OnImageShort
);
n
.
subscribe
(
FLAGS_image_short_topic
,
1000
,
OnImageShort
);
...
@@ -80,9 +77,6 @@ void OnImage(CameraId camera_id, const sensor_msgs::ImagePtr &msg) {
...
@@ -80,9 +77,6 @@ void OnImage(CameraId camera_id, const sensor_msgs::ImagePtr &msg) {
g_cached_images
.
erase
(
g_cached_images
.
begin
());
g_cached_images
.
erase
(
g_cached_images
.
begin
());
}
}
}
}
void
OnImageLong
(
const
sensor_msgs
::
ImagePtr
&
msg
)
{
OnImage
(
CameraId
::
LONG_FOCUS
,
msg
);
}
void
OnImageShort
(
const
sensor_msgs
::
ImagePtr
&
msg
)
{
void
OnImageShort
(
const
sensor_msgs
::
ImagePtr
&
msg
)
{
OnImage
(
CameraId
::
SHORT_FOCUS
,
msg
);
OnImage
(
CameraId
::
SHORT_FOCUS
,
msg
);
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录