Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
9e33ae6f
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 搜索 >>
提交
9e33ae6f
编写于
10月 17, 2018
作者:
C
Calvin Miao
提交者:
Jiangtao Hu
12月 13, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Perception: fixed misusing of logging
上级
d95857ff
变更
9
隐藏空白更改
内联
并排
Showing
9 changed file
with
58 addition
and
78 deletion
+58
-78
modules/perception/base/BUILD
modules/perception/base/BUILD
+1
-0
modules/perception/base/blob.h
modules/perception/base/blob.h
+1
-1
modules/perception/base/syncedmem.h
modules/perception/base/syncedmem.h
+1
-1
modules/perception/camera/common/util.h
modules/perception/camera/common/util.h
+47
-62
modules/perception/camera/lib/obstacle/tracker/common/BUILD
modules/perception/camera/lib/obstacle/tracker/common/BUILD
+1
-2
modules/perception/camera/test/BUILD
modules/perception/camera/test/BUILD
+2
-1
modules/perception/camera/test/camera_common_undistortion.cc
modules/perception/camera/test/camera_common_undistortion.cc
+1
-7
modules/perception/camera/test/camera_lib_lane_detector_denseline_lane_detector_test.cc
.../camera_lib_lane_detector_denseline_lane_detector_test.cc
+3
-2
modules/perception/camera/test/camera_lib_traffic_light_tracker_test.cc
...tion/camera/test/camera_lib_traffic_light_tracker_test.cc
+1
-2
未找到文件。
modules/perception/base/BUILD
浏览文件 @
9e33ae6f
...
...
@@ -45,6 +45,7 @@ cc_library(
"blob.h"
,
],
deps
=
[
"//cybertron"
,
":common"
,
":syncedmem"
,
],
...
...
modules/perception/base/blob.h
浏览文件 @
9e33ae6f
...
...
@@ -19,7 +19,7 @@
#include <string>
#include <vector>
#include "
glog/loggin
g.h"
#include "
cybertron/common/lo
g.h"
#include "modules/perception/base/syncedmem.h"
namespace
apollo
{
...
...
modules/perception/base/syncedmem.h
浏览文件 @
9e33ae6f
...
...
@@ -18,7 +18,7 @@
#include <cstdlib>
#include <iostream>
#include "
glog/loggin
g.h"
#include "
cybertron/common/lo
g.h"
#include "modules/perception/base/common.h"
namespace
apollo
{
...
...
modules/perception/camera/common/util.h
浏览文件 @
9e33ae6f
/******************************************************************************
* Copyright 2018 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the License);
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
* Copyright 2018 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the License);
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include <fcntl.h>
#include <cblas.h>
#include <google/protobuf/io/coded_stream.h>
#include <google/protobuf/io/zero_copy_stream_impl.h>
#include <google/protobuf/io/gzip_stream.h>
#include <google/protobuf/io/zero_copy_stream_impl.h>
#include <google/protobuf/text_format.h>
#include <cblas.h>
#include <algorithm>
#include <fstream>
#include <iostream>
...
...
@@ -29,7 +28,8 @@
#include <numeric>
#include <string>
#include <vector>
#include "glog/logging.h"
#include "cybertron/common/log.h"
#include "modules/perception/base/blob.h"
#include "modules/perception/base/image.h"
#include "modules/perception/base/object.h"
...
...
@@ -43,16 +43,14 @@ bool Equal(float x, float target, float eps = 1e-6);
bool
Equal
(
double
x
,
double
target
,
double
eps
=
1e-6
);
// @brief whether rect1 is covered by rect2
template
<
typename
T
>
bool
IsCovered
(
const
base
::
Rect
<
T
>
&
rect1
,
const
base
::
Rect
<
T
>
&
rect2
,
template
<
typename
T
>
bool
IsCovered
(
const
base
::
Rect
<
T
>
&
rect1
,
const
base
::
Rect
<
T
>
&
rect2
,
float
thresh
)
{
base
::
RectF
inter
=
rect1
&
rect2
;
return
inter
.
Area
()
/
rect1
.
Area
()
>
thresh
;
}
template
<
typename
T
>
bool
IsCoveredHorizon
(
const
base
::
Rect
<
T
>
&
rect1
,
const
base
::
Rect
<
T
>
&
rect2
,
template
<
typename
T
>
bool
IsCoveredHorizon
(
const
base
::
Rect
<
T
>
&
rect1
,
const
base
::
Rect
<
T
>
&
rect2
,
float
thresh
)
{
base
::
RectF
inter
=
rect1
&
rect2
;
if
(
inter
.
Area
()
>
0
)
{
...
...
@@ -60,9 +58,8 @@ bool IsCoveredHorizon(const base::Rect<T> &rect1,
}
return
false
;
}
template
<
typename
T
>
bool
IsCoveredVertical
(
const
base
::
Rect
<
T
>
&
rect1
,
const
base
::
Rect
<
T
>
&
rect2
,
template
<
typename
T
>
bool
IsCoveredVertical
(
const
base
::
Rect
<
T
>
&
rect1
,
const
base
::
Rect
<
T
>
&
rect2
,
float
thresh
)
{
base
::
RectF
inter
=
rect1
&
rect2
;
if
(
inter
.
Area
()
>
0
)
{
...
...
@@ -71,7 +68,7 @@ bool IsCoveredVertical(const base::Rect<T> &rect1,
return
false
;
}
template
<
typename
T
>
template
<
typename
T
>
bool
Contain
(
const
std
::
vector
<
T
>
&
array
,
const
T
&
element
)
{
for
(
const
auto
&
item
:
array
)
{
if
(
item
==
element
)
{
...
...
@@ -81,33 +78,26 @@ bool Contain(const std::vector<T> &array, const T &element) {
return
false
;
}
template
<
typename
T
>
bool
OutOfValidRegion
(
const
base
::
BBox2D
<
T
>
box
,
const
T
width
,
const
T
height
,
template
<
typename
T
>
bool
OutOfValidRegion
(
const
base
::
BBox2D
<
T
>
box
,
const
T
width
,
const
T
height
,
const
T
border_size
=
0
)
{
if
(
box
.
xmin
<
border_size
||
box
.
ymin
<
border_size
)
{
return
true
;
}
if
(
box
.
xmax
+
border_size
>
width
||
box
.
ymax
+
border_size
>
height
)
{
if
(
box
.
xmax
+
border_size
>
width
||
box
.
ymax
+
border_size
>
height
)
{
return
true
;
}
return
false
;
}
template
<
typename
T
>
bool
OutOfValidRegion
(
const
base
::
Rect
<
T
>
rect
,
const
T
width
,
const
T
height
,
template
<
typename
T
>
bool
OutOfValidRegion
(
const
base
::
Rect
<
T
>
rect
,
const
T
width
,
const
T
height
,
const
T
border_size
=
0
)
{
base
::
BBox2D
<
T
>
box
(
rect
);
return
OutOfValidRegion
(
box
,
width
,
height
,
border_size
);
}
template
<
typename
T
>
void
RefineBox
(
const
base
::
Rect
<
T
>
&
box_in
,
const
T
width
,
const
T
height
,
template
<
typename
T
>
void
RefineBox
(
const
base
::
Rect
<
T
>
&
box_in
,
const
T
width
,
const
T
height
,
base
::
Rect
<
T
>
*
box_out
)
{
if
(
!
box_out
)
{
return
;
...
...
@@ -129,10 +119,11 @@ void RefineBox(const base::Rect<T> &box_in,
box_out
->
y
=
0
;
box_out
->
height
=
0
;
}
box_out
->
width
=
(
box_out
->
x
+
box_out
->
width
<=
width
)
?
box_out
->
width
:
width
-
box_out
->
x
;
box_out
->
height
=
(
box_out
->
y
+
box_out
->
height
<=
height
)
?
box_out
->
height
:
height
-
box_out
->
y
;
box_out
->
width
=
(
box_out
->
x
+
box_out
->
width
<=
width
)
?
box_out
->
width
:
width
-
box_out
->
x
;
box_out
->
height
=
(
box_out
->
y
+
box_out
->
height
<=
height
)
?
box_out
->
height
:
height
-
box_out
->
y
;
if
(
box_out
->
width
<
0
)
{
box_out
->
width
=
0
;
}
...
...
@@ -141,10 +132,8 @@ void RefineBox(const base::Rect<T> &box_in,
}
}
template
<
typename
T
>
void
RefineBox
(
const
base
::
BBox2D
<
T
>
&
box_in
,
const
T
width
,
const
T
height
,
template
<
typename
T
>
void
RefineBox
(
const
base
::
BBox2D
<
T
>
&
box_in
,
const
T
width
,
const
T
height
,
base
::
BBox2D
<
T
>
*
box_out
)
{
if
(
!
box_out
)
{
return
;
...
...
@@ -157,21 +146,18 @@ void RefineBox(const base::BBox2D<T> &box_in,
bool
LoadAnchors
(
const
std
::
string
&
path
,
std
::
vector
<
float
>
*
anchors
);
bool
LoadTypes
(
const
std
::
string
&
path
,
std
::
vector
<
base
::
ObjectSubType
>
*
types
);
bool
LoadExpand
(
const
std
::
string
&
path
,
std
::
vector
<
float
>
*
expands
);
bool
LoadExpand
(
const
std
::
string
&
path
,
std
::
vector
<
float
>
*
expands
);
bool
ResizeCPU
(
const
base
::
Blob
<
uint8_t
>
&
src_gpu
,
std
::
shared_ptr
<
base
::
Blob
<
float
>
>
dst
,
int
stepwidth
,
std
::
shared_ptr
<
base
::
Blob
<
float
>>
dst
,
int
stepwidth
,
int
start_axis
);
void
GetCybertronWorkRoot
(
std
::
string
*
work_root
);
void
FillObjectPolygonFromBBox3D
(
base
::
Object
*
object_ptr
);
template
<
typename
T
>
void
CalculateMeanAndVariance
(
const
std
::
vector
<
T
>
&
data
,
T
*
mean
,
T
*
variance
)
{
template
<
typename
T
>
void
CalculateMeanAndVariance
(
const
std
::
vector
<
T
>
&
data
,
T
*
mean
,
T
*
variance
)
{
if
(
!
mean
||
!
variance
)
{
return
;
}
...
...
@@ -184,11 +170,10 @@ void CalculateMeanAndVariance(const std::vector<T> &data,
*
mean
=
sum
/
data
.
size
();
std
::
vector
<
T
>
diff
(
data
.
size
());
std
::
transform
(
data
.
begin
(),
data
.
end
(),
diff
.
begin
(),
[
mean
](
T
x
)
{
return
x
-
*
mean
;
});
std
::
transform
(
data
.
begin
(),
data
.
end
(),
diff
.
begin
(),
[
mean
](
T
x
)
{
return
x
-
*
mean
;
});
T
sum_of_diff_sqrs
=
std
::
inner_product
(
diff
.
begin
(),
diff
.
end
(),
diff
.
begin
(),
static_cast
<
T
>
(
0
));
diff
.
begin
(),
static_cast
<
T
>
(
0
));
*
variance
=
sum_of_diff_sqrs
/
data
.
size
();
}
...
...
modules/perception/camera/lib/obstacle/tracker/common/BUILD
浏览文件 @
9e33ae6f
...
...
@@ -14,8 +14,7 @@ cuda_library(
deps
=
[
"@cuda"
,
"//cybertron"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/camera/common:camera_frame"
,
"//modules/perception/inference/utils:inference_gemm_lib"
,
],
)
...
...
modules/perception/camera/test/BUILD
浏览文件 @
9e33ae6f
...
...
@@ -385,7 +385,7 @@
# "-lopencv_highgui",
# ],
# deps = [
# "//
external:gflags
",
# "//
cybertron
",
# "//modules/perception/camera/lib/lane/detector/denseline:denseline_lane_detector",
# "//modules/perception/base:base",
# "//modules/perception/common/io:io_util",
...
...
@@ -712,6 +712,7 @@
# "-lcaffe",
# ],
# deps = [
# "//cybertron",
# "//modules/perception/base:distortion_model",
# "//modules/perception/common/io:io_util",
# "//modules/perception/camera/lib/traffic_light/tracker:semantic_decision",
...
...
modules/perception/camera/test/camera_common_undistortion.cc
浏览文件 @
9e33ae6f
...
...
@@ -14,19 +14,14 @@
* limitations under the License.
*****************************************************************************/
#include "modules/perception/camera/test/camera_common_undistortion.h"
#include <npp.h>
#include <
glog/logging
.h>
#include <
npp
.h>
#include <boost/filesystem.hpp>
#include <yaml-cpp/yaml.h>
#include <opencv2/core/core.hpp>
#include <opencv2/opencv.hpp>
#include <vector>
// #include "cybertron/common/log.h"
namespace
apollo
{
namespace
perception
{
namespace
camera
{
...
...
@@ -169,7 +164,6 @@ int ImageGpuPreprocessHandler::load_camera_intrinsics(
<<
"File not exists: "
<<
intrinsics_path
;
YAML
::
Node
node
=
YAML
::
LoadFile
(
intrinsics_path
);
if
(
node
.
IsNull
())
{
// AINFO << "Load " << intrinsics_path << " failed! please check!";
return
-
1
;
}
D
->
resize
(
node
[
"D"
].
size
());
...
...
modules/perception/camera/test/camera_lib_lane_detector_denseline_lane_detector_test.cc
浏览文件 @
9e33ae6f
...
...
@@ -13,13 +13,14 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include <gtest/gtest.h>
#include <opencv2/opencv.hpp>
#include <fstream>
#include <iostream>
#include "cybertron/common/log.h"
#include "modules/perception/camera/lib/lane/detector/denseline/denseline_lane_detector.h"
#include "glog/logging.h"
#include "gflags/gflags.h"
#include "modules/perception/base/distortion_model.h"
#include "modules/perception/common/io/io_util.h"
...
...
modules/perception/camera/test/camera_lib_traffic_light_tracker_test.cc
浏览文件 @
9e33ae6f
...
...
@@ -18,9 +18,8 @@
#include <iostream>
#include "gtest/gtest.h"
#include "glog/logging.h"
#include "gflags/gflags.h"
#include "cybertron/common/log.h"
#include "modules/perception/base/distortion_model.h"
#include "modules/perception/common/io/io_util.h"
#include "modules/perception/camera/lib/traffic_light/tracker/semantic_decision.h"
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录