Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
8047dffb
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 搜索 >>
提交
8047dffb
编写于
10月 16, 2018
作者:
W
wangxuehui
提交者:
Liangliang Zhang
10月 17, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
perception: remove lib/io/protobuf_util.h file, fix size_t type
上级
4c76cc6c
变更
71
隐藏空白更改
内联
并排
Showing
71 changed file
with
254 addition
and
338 deletion
+254
-338
modules/perception/camera/app/BUILD
modules/perception/camera/app/BUILD
+5
-8
modules/perception/camera/app/debug_info.cc
modules/perception/camera/app/debug_info.cc
+7
-11
modules/perception/camera/app/debug_info.h
modules/perception/camera/app/debug_info.h
+1
-1
modules/perception/camera/app/obstacle_camera_perception.cc
modules/perception/camera/app/obstacle_camera_perception.cc
+11
-11
modules/perception/camera/app/traffic_light_camera_perception.cc
.../perception/camera/app/traffic_light_camera_perception.cc
+5
-5
modules/perception/camera/app/traffic_light_camera_perception.h
...s/perception/camera/app/traffic_light_camera_perception.h
+2
-2
modules/perception/camera/common/BUILD
modules/perception/camera/common/BUILD
+2
-6
modules/perception/camera/common/camera_ground_plane.cc
modules/perception/camera/common/camera_ground_plane.cc
+1
-1
modules/perception/camera/common/data_provider.cc
modules/perception/camera/common/data_provider.cc
+1
-1
modules/perception/camera/common/object_template_manager.cc
modules/perception/camera/common/object_template_manager.cc
+4
-3
modules/perception/camera/common/object_template_manager.h
modules/perception/camera/common/object_template_manager.h
+1
-1
modules/perception/camera/common/twod_threed_util.h
modules/perception/camera/common/twod_threed_util.h
+1
-3
modules/perception/camera/common/undistortion_handler.h
modules/perception/camera/common/undistortion_handler.h
+1
-1
modules/perception/camera/common/util.h
modules/perception/camera/common/util.h
+8
-8
modules/perception/camera/lib/calibration_service/online_calibration_service/BUILD
.../lib/calibration_service/online_calibration_service/BUILD
+1
-1
modules/perception/camera/lib/calibrator/laneline/BUILD
modules/perception/camera/lib/calibrator/laneline/BUILD
+0
-2
modules/perception/camera/lib/calibrator/laneline/laneline_calibrator.cc
...ion/camera/lib/calibrator/laneline/laneline_calibrator.cc
+1
-1
modules/perception/camera/lib/feature_extractor/tfe/BUILD
modules/perception/camera/lib/feature_extractor/tfe/BUILD
+6
-4
modules/perception/camera/lib/feature_extractor/tfe/external_feature_extractor.cc
...a/lib/feature_extractor/tfe/external_feature_extractor.cc
+6
-4
modules/perception/camera/lib/feature_extractor/tfe/project_feature.cc
...ption/camera/lib/feature_extractor/tfe/project_feature.cc
+3
-3
modules/perception/camera/lib/feature_extractor/tfe/tracking_feat_extractor.cc
...mera/lib/feature_extractor/tfe/tracking_feat_extractor.cc
+2
-2
modules/perception/camera/lib/interface/BUILD
modules/perception/camera/lib/interface/BUILD
+0
-3
modules/perception/camera/lib/lane/detector/denseline/BUILD
modules/perception/camera/lib/lane/detector/denseline/BUILD
+4
-4
modules/perception/camera/lib/lane/detector/denseline/denseline_lane_detector.cc
...ra/lib/lane/detector/denseline/denseline_lane_detector.cc
+2
-2
modules/perception/camera/lib/lane/postprocessor/denseline/BUILD
.../perception/camera/lib/lane/postprocessor/denseline/BUILD
+3
-3
modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.cc
...e/postprocessor/denseline/denseline_lane_postprocessor.cc
+6
-6
modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.h
...ne/postprocessor/denseline/denseline_lane_postprocessor.h
+1
-1
modules/perception/camera/lib/obstacle/detector/yolo/BUILD
modules/perception/camera/lib/obstacle/detector/yolo/BUILD
+4
-4
modules/perception/camera/lib/obstacle/detector/yolo/region_output.cu
...eption/camera/lib/obstacle/detector/yolo/region_output.cu
+12
-12
modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.cc
...mera/lib/obstacle/detector/yolo/yolo_obstacle_detector.cc
+3
-3
modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.h
...amera/lib/obstacle/detector/yolo/yolo_obstacle_detector.h
+10
-9
modules/perception/camera/lib/obstacle/postprocessor/location_refiner/BUILD
.../camera/lib/obstacle/postprocessor/location_refiner/BUILD
+2
-2
modules/perception/camera/lib/obstacle/postprocessor/location_refiner/location_refiner_obstacle_postprocessor.cc
...cation_refiner/location_refiner_obstacle_postprocessor.cc
+5
-5
modules/perception/camera/lib/obstacle/tracker/common/kalman_filter.cc
...ption/camera/lib/obstacle/tracker/common/kalman_filter.cc
+1
-1
modules/perception/camera/lib/obstacle/tracker/common/similar.cc
.../perception/camera/lib/obstacle/tracker/common/similar.cc
+1
-1
modules/perception/camera/lib/obstacle/tracker/omt/BUILD
modules/perception/camera/lib/obstacle/tracker/omt/BUILD
+4
-3
modules/perception/camera/lib/obstacle/tracker/omt/obstacle_reference.cc
...ion/camera/lib/obstacle/tracker/omt/obstacle_reference.cc
+1
-1
modules/perception/camera/lib/obstacle/tracker/omt/omt_obstacle_tracker.cc
...n/camera/lib/obstacle/tracker/omt/omt_obstacle_tracker.cc
+16
-14
modules/perception/camera/lib/obstacle/tracker/omt/target.cc
modules/perception/camera/lib/obstacle/tracker/omt/target.cc
+2
-2
modules/perception/camera/lib/obstacle/transformer/multicue/BUILD
...perception/camera/lib/obstacle/transformer/multicue/BUILD
+2
-2
modules/perception/camera/lib/obstacle/transformer/multicue/multicue_obstacle_transformer.cc
...cle/transformer/multicue/multicue_obstacle_transformer.cc
+3
-3
modules/perception/camera/lib/traffic_light/detector/detection/BUILD
...ception/camera/lib/traffic_light/detector/detection/BUILD
+4
-4
modules/perception/camera/lib/traffic_light/detector/detection/detection.cc
.../camera/lib/traffic_light/detector/detection/detection.cc
+5
-5
modules/perception/camera/lib/traffic_light/detector/detection/select.cc
...ion/camera/lib/traffic_light/detector/detection/select.cc
+3
-3
modules/perception/camera/lib/traffic_light/detector/recognition/BUILD
...ption/camera/lib/traffic_light/detector/recognition/BUILD
+6
-6
modules/perception/camera/lib/traffic_light/detector/recognition/classify.cc
...camera/lib/traffic_light/detector/recognition/classify.cc
+1
-1
modules/perception/camera/lib/traffic_light/detector/recognition/recognition.cc
...era/lib/traffic_light/detector/recognition/recognition.cc
+2
-2
modules/perception/camera/lib/traffic_light/preprocessor/BUILD
...es/perception/camera/lib/traffic_light/preprocessor/BUILD
+3
-4
modules/perception/camera/lib/traffic_light/preprocessor/multi_camera_projection.cc
...lib/traffic_light/preprocessor/multi_camera_projection.cc
+4
-4
modules/perception/camera/lib/traffic_light/preprocessor/tl_preprocessor.cc
.../camera/lib/traffic_light/preprocessor/tl_preprocessor.cc
+4
-4
modules/perception/camera/lib/traffic_light/tracker/BUILD
modules/perception/camera/lib/traffic_light/tracker/BUILD
+1
-1
modules/perception/camera/lib/traffic_light/tracker/semantic_decision.cc
...ion/camera/lib/traffic_light/tracker/semantic_decision.cc
+5
-5
modules/perception/camera/test/BUILD
modules/perception/camera/test/BUILD
+2
-2
modules/perception/camera/test/camera_common_util_test.cc
modules/perception/camera/test/camera_common_util_test.cc
+2
-2
modules/perception/camera/test/camera_lib_obstacle_detector_yolo_yolo_obstacle_detector_test.cc
...lib_obstacle_detector_yolo_yolo_obstacle_detector_test.cc
+4
-4
modules/perception/camera/test/camera_lib_obstacle_tracker_common_test.cc
...on/camera/test/camera_lib_obstacle_tracker_common_test.cc
+1
-1
modules/perception/camera/test/camera_lib_obstacle_tracker_omt_reference_test.cc
...ra/test/camera_lib_obstacle_tracker_omt_reference_test.cc
+3
-3
modules/perception/camera/test/camera_lib_obstacle_tracker_omt_target_test.cc
...amera/test/camera_lib_obstacle_tracker_omt_target_test.cc
+9
-9
modules/perception/camera/test/camera_lib_traffic_light_detector_recognition_test.cc
...est/camera_lib_traffic_light_detector_recognition_test.cc
+0
-7
modules/perception/camera/test/camera_lib_traffic_light_tracker_test.cc
...tion/camera/test/camera_lib_traffic_light_tracker_test.cc
+8
-8
modules/perception/camera/tools/lane_detection/BUILD
modules/perception/camera/tools/lane_detection/BUILD
+4
-4
modules/perception/camera/tools/lane_detection/lane_common.cc
...les/perception/camera/tools/lane_detection/lane_common.cc
+22
-26
modules/perception/camera/tools/obstacle_detection/BUILD
modules/perception/camera/tools/obstacle_detection/BUILD
+1
-1
modules/perception/camera/tools/offline/BUILD
modules/perception/camera/tools/offline/BUILD
+1
-1
modules/perception/camera/tools/offline/offline_obstacle_pipeline.cc
...ception/camera/tools/offline/offline_obstacle_pipeline.cc
+2
-2
modules/perception/camera/tools/offline/visualizer.cc
modules/perception/camera/tools/offline/visualizer.cc
+1
-1
modules/perception/lib/io/BUILD
modules/perception/lib/io/BUILD
+0
-11
modules/perception/lib/io/protobuf_util.h
modules/perception/lib/io/protobuf_util.h
+0
-52
modules/perception/onboard/component/BUILD
modules/perception/onboard/component/BUILD
+1
-1
modules/perception/onboard/component/fusion_camera_detection_component.cc
...on/onboard/component/fusion_camera_detection_component.cc
+2
-2
modules/perception/onboard/component/trafficlights_perception_component.cc
...n/onboard/component/trafficlights_perception_component.cc
+2
-2
未找到文件。
modules/perception/camera/app/BUILD
浏览文件 @
8047dffb
...
...
@@ -29,7 +29,6 @@ cc_library(
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
# "//modules/perception/camera/lib/calibration_service/online_calibration_service:online_calibration_service",
],
)
...
...
@@ -47,10 +46,10 @@ cc_library(
"@yaml_cpp//:yaml"
,
"//external:gflags"
,
"//cybertron"
,
"//modules/common/util:file_util"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/camera/lib/calibration_service/online_calibration_service:online_calibration_service"
,
"//modules/perception/camera/lib/calibrator/laneline:laneline_calibrator"
,
"//modules/perception/camera/lib/feature_extractor/tfe:external_feature_extractor"
,
...
...
@@ -62,13 +61,11 @@ cc_library(
"//modules/perception/camera/lib/obstacle/postprocessor/location_refiner:location_refiner_obstacle_postprocessor"
,
"//modules/perception/camera/lib/obstacle/tracker/omt:omt_obstacle_tracker"
,
"//modules/perception/camera/lib/obstacle/transformer/multicue:multicue_obstacle_transformer"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/inference/utils:inference_cuda_util_lib"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
"//modules/perception/lib/utils:utils"
,
"//modules/perception/lib/singleton:singleton"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/inference/utils:inference_cuda_util_lib"
,
],
)
...
...
@@ -84,13 +81,13 @@ cc_library(
deps
=
[
":camera_app_lib_proto"
,
"//cybertron"
,
"//modules/common/util:file_util"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/camera/lib/traffic_light/detector/detection:detection"
,
"//modules/perception/camera/lib/traffic_light/detector/recognition:recognition"
,
"//modules/perception/camera/lib/traffic_light/tracker:semantic_decision"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
"//modules/perception/lib/utils:utils"
,
],
)
...
...
modules/perception/camera/app/debug_info.cc
浏览文件 @
8047dffb
...
...
@@ -67,7 +67,7 @@ void WriteTracking(std::ofstream &fout,
return
;
}
char
output
[
500
];
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
tracked_object
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
tracked_object
.
size
(
);
++
i
)
{
base
::
ObjectPtr
ptr
=
tracked_object
[
i
];
snprintf
(
output
,
sizeof
(
output
),
...
...
@@ -256,8 +256,8 @@ int WriteLanelines(const bool enable,
// camera_image_point_set
fprintf
(
file_save
,
"
\"
camera_point_set
\"
:
\n
"
);
fprintf
(
file_save
,
"["
);
for
(
int
k
=
0
;
k
<
static_cast
<
int
>
(
camera_point_set
.
size
()
);
k
++
)
{
if
(
k
<
static_cast
<
int
>
(
camera_point_set
.
size
()
)
-
1
)
{
for
(
size_t
k
=
0
;
k
<
camera_point_set
.
size
(
);
k
++
)
{
if
(
k
<
camera_point_set
.
size
(
)
-
1
)
{
fprintf
(
file_save
,
"{
\"
x
\"
:%.4f,
\"
y
\"
:%.4f,
\"
z
\"
:%.4f},"
,
camera_point_set
[
k
].
x
,
camera_point_set
[
k
].
y
,
camera_point_set
[
k
].
z
);
...
...
@@ -280,9 +280,8 @@ int WriteLanelines(const bool enable,
// curve_image_point_set
fprintf
(
file_save
,
"
\"
image_point_set
\"
:
\n
"
);
fprintf
(
file_save
,
"["
);
for
(
int
k
=
0
;
k
<
static_cast
<
int
>
(
image_point_set
.
size
());
k
++
)
{
if
(
k
<
static_cast
<
int
>
(
image_point_set
.
size
())
-
1
)
{
for
(
size_t
k
=
0
;
k
<
image_point_set
.
size
();
k
++
)
{
if
(
k
<
image_point_set
.
size
()
-
1
)
{
fprintf
(
file_save
,
"{
\"
x
\"
:%.4f,
\"
y
\"
:%.4f},"
,
image_point_set
[
k
].
x
,
image_point_set
[
k
].
y
);
}
else
{
...
...
@@ -333,11 +332,8 @@ void WriteFusionTracking(std::ofstream &fout,
}
AINFO
<<
"Write track results:"
<<
frame_num
;
if
(
camera_name
==
"onsemi_narrow"
)
{
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
tracked_object
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
tracked_object
.
size
(
);
++
i
)
{
base
::
ObjectPtr
ptr
=
tracked_object
[
i
];
// if (ptr->camera_supplement.sensor_name == "onsemi_obstacle") {
// continue; // do not show the 6mm target in the 12mm camera
// }
char
output
[
300
];
snprintf
(
output
,
sizeof
(
output
),
...
...
@@ -366,7 +362,7 @@ void WriteFusionTracking(std::ofstream &fout,
fout
<<
output
<<
std
::
endl
;
}
}
else
if
(
camera_name
==
"onsemi_obstacle"
)
{
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
tracked_object
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
tracked_object
.
size
(
);
++
i
)
{
base
::
ObjectPtr
ptr
=
tracked_object
[
i
];
char
output
[
300
];
snprintf
(
output
,
...
...
modules/perception/camera/app/debug_info.h
浏览文件 @
8047dffb
...
...
@@ -18,8 +18,8 @@
#include <fstream>
#include <string>
#include <vector>
#include "modules/perception/camera/common/camera_frame.h"
#include "modules/perception/base/object.h"
#include "modules/perception/camera/common/camera_frame.h"
#include "modules/perception/camera/lib/interface/base_calibration_service.h"
namespace
apollo
{
...
...
modules/perception/camera/app/obstacle_camera_perception.cc
浏览文件 @
8047dffb
...
...
@@ -16,22 +16,22 @@
#include "modules/perception/camera/app/obstacle_camera_perception.h"
#include <gflags/gflags.h>
#include <yaml-cpp/yaml.h>
#include <algorithm>
#include <fstream>
#include <string>
#include <vector>
#include <algorithm>
#include <utility>
#include <vector>
#include "cybertron/common/log.h"
#include "modules/perception/inference/utils/cuda_util.h"
#include "modules/perception/common/io/io_util.h"
#include "modules/common/util/file.h"
#include "modules/perception/base/object.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/lib/utils/perf.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/camera/common/global_config.h"
#include "modules/perception/camera/app/debug_info.h"
#include "modules/perception/camera/common/global_config.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/common/io/io_util.h"
#include "modules/perception/inference/utils/cuda_util.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/lib/utils/perf.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -47,7 +47,7 @@ bool ObstacleCameraPerception::Init(
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
config_file
=
lib
::
FileUtil
::
GetAbsolutePath
(
work_root
,
config_file
);
CHECK
(
lib
::
ParseProtobuf
FromFile
<
app
::
PerceptionParam
>
(
CHECK
(
apollo
::
common
::
util
::
GetProto
FromFile
<
app
::
PerceptionParam
>
(
config_file
,
&
perception_param_
))
<<
"Read config failed: "
;
CHECK
(
inference
::
CudaUtil
::
set_device_id
(
perception_param_
.
gpu_id
()));
...
...
@@ -392,7 +392,7 @@ bool ObstacleCameraPerception::Perception(
std
::
to_string
(
frame
->
frame_id
)
+
".txt"
,
frame
);
// set the sensor name of each object
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
frame
->
detected_objects
.
size
()
);
i
++
)
{
for
(
size_t
i
=
0
;
i
<
frame
->
detected_objects
.
size
(
);
i
++
)
{
frame
->
detected_objects
[
i
]
->
camera_supplement
.
sensor_name
=
frame
->
data_provider
->
sensor_name
();
}
...
...
modules/perception/camera/app/traffic_light_camera_perception.cc
浏览文件 @
8047dffb
...
...
@@ -19,13 +19,13 @@
#include <string>
#include "cybertron/common/log.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/lib/utils/perf.h"
#include "modules/common/util/file.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/camera/lib/traffic_light/detector/detection/detection.h"
#include "modules/perception/camera/lib/traffic_light/detector/recognition/recognition.h"
#include "modules/perception/camera/lib/traffic_light/tracker/semantic_decision.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/utils/perf.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -41,7 +41,7 @@ bool TrafficLightCameraPerception::Init(
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
proto_path
=
lib
::
FileUtil
::
GetAbsolutePath
(
work_root
,
proto_path
);
AINFO
<<
"proto_path "
<<
proto_path
;
if
(
!
lib
::
ParseProtobuf
FromFile
(
proto_path
,
&
tl_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
proto_path
,
&
tl_param_
))
{
AINFO
<<
"load proto param failed, root dir: "
<<
options
.
root_dir
;
return
false
;
}
...
...
modules/perception/camera/app/traffic_light_camera_perception.h
浏览文件 @
8047dffb
...
...
@@ -17,13 +17,13 @@
#include <memory>
#include <string>
#include "modules/perception/camera/app/perception.pb.h"
#include "modules/perception/camera/common/camera_frame.h"
#include "modules/perception/camera/lib/interface/base_camera_perception.h"
#include "modules/perception/camera/lib/interface/base_feature_extractor.h"
#include "modules/perception/camera/lib/interface/base_init_options.h"
#include "modules/perception/camera/common/camera_frame.h"
#include "modules/perception/camera/lib/interface/base_traffic_light_tracker.h"
#include "modules/perception/camera/lib/interface/base_traffic_light_detector.h"
#include "modules/perception/camera/app/perception.pb.h"
namespace
apollo
{
namespace
perception
{
...
...
modules/perception/camera/common/BUILD
浏览文件 @
8047dffb
...
...
@@ -3,7 +3,6 @@ load("//tools:cpplint.bzl", "cpplint")
package
(
default_visibility
=
[
"//visibility:public"
])
cc_library
(
name
=
"camera_frame"
,
hdrs
=
[
...
...
@@ -29,8 +28,6 @@ cc_library(
"//modules/perception/common/i_lib/core:core"
,
"//modules/perception/common/i_lib/da:i_ransac"
,
"//modules/perception/common/i_lib/geometry:i_plane"
,
#"//modules/perception/common/i_lib/geometry:i_util",
#"//modules/perception/common/i_lib/numeric:numeric",
],
)
...
...
@@ -78,14 +75,14 @@ cc_library(
deps
=
[
"//external:gflags"
,
"//cybertron"
,
"//modules/common/util:file_util"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common/proto:object_template_meta_schema_proto"
,
"//modules/perception/common/io:io_util"
,
"//modules/perception/lib/config_manager:config_manager"
,
"//modules/perception/lib/io:protobuf_util"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/singleton:singleton"
,
"//modules/perception/lib/thread:thread"
,
"//modules/perception/camera/common/proto:object_template_meta_schema_proto"
,
],
)
...
...
@@ -107,7 +104,6 @@ cc_library(
"@eigen"
,
"//modules/perception/common/i_lib/core:core"
,
"//modules/perception/common/i_lib/geometry:i_plane"
,
#"//modules/perception/common/i_lib/geometry:i_util",
],
)
...
...
modules/perception/camera/common/camera_ground_plane.cc
浏览文件 @
8047dffb
...
...
@@ -19,8 +19,8 @@
#include <utility>
#include "cybertron/common/log.h"
#include "modules/perception/common/i_lib/geometry/i_util.h"
#include "modules/perception/common/i_lib/da/i_ransac.h"
#include "modules/perception/common/i_lib/geometry/i_util.h"
namespace
apollo
{
...
...
modules/perception/camera/common/data_provider.cc
浏览文件 @
8047dffb
...
...
@@ -13,8 +13,8 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "cybertron/common/log.h"
#include "modules/perception/camera/common/data_provider.h"
#include "cybertron/common/log.h"
namespace
apollo
{
namespace
perception
{
...
...
modules/perception/camera/common/object_template_manager.cc
浏览文件 @
8047dffb
...
...
@@ -24,10 +24,10 @@
#include <utility>
#include "cybertron/common/log.h"
#include "modules/common/util/file.h"
#include "modules/perception/common/io/io_util.h"
#include "modules/perception/lib/config_manager/config_manager.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -63,7 +63,8 @@ bool ObjectTemplateManager::Init(
std
::
string
config
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
ObjectTemplateMeta
proto
;
if
(
!
lib
::
ParseProtobufFromFile
<
ObjectTemplateMeta
>
(
config
,
&
proto
))
{
if
(
!
apollo
::
common
::
util
::
GetProtoFromFile
<
ObjectTemplateMeta
>
(
config
,
&
proto
))
{
AERROR
<<
"Read config failed: "
<<
config
;
return
false
;
}
...
...
@@ -187,7 +188,7 @@ void ObjectTemplateManager::LoadVehTemplates(const ObjectTemplate &tmplt) {
list_tpl
.
push_back
(
std
::
make_tuple
(
dim
.
h
(),
dim
.
w
(),
dim
.
l
()));
}
std
::
sort
(
list_tpl
.
begin
(),
list_tpl
.
end
());
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
list_tpl
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
list_tpl
.
size
(
);
++
i
)
{
veh_hwl_
.
push_back
(
std
::
get
<
0
>
(
list_tpl
[
i
]));
veh_hwl_
.
push_back
(
std
::
get
<
1
>
(
list_tpl
[
i
]));
veh_hwl_
.
push_back
(
std
::
get
<
2
>
(
list_tpl
[
i
]));
...
...
modules/perception/camera/common/object_template_manager.h
浏览文件 @
8047dffb
...
...
@@ -24,10 +24,10 @@
#include <unordered_map>
#include <vector>
#include "gflags/gflags.h"
#include "cybertron/common/log.h"
#include "modules/perception/base/object_types.h"
#include "modules/perception/camera/common/proto/object_template_meta_schema.pb.h"
#include "gflags/gflags.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/lib/thread/mutex.h"
...
...
modules/perception/camera/common/twod_threed_util.h
浏览文件 @
8047dffb
...
...
@@ -16,15 +16,13 @@
#pragma once
#include <float.h>
#include <Eigen/Dense>
#include <algorithm>
#include <cstdlib>
#include <utility>
#include <vector>
#include <algorithm>
#include "cybertron/common/log.h"
#include "modules/perception/common/i_lib/core/i_constant.h"
#include "modules/perception/common/i_lib/geometry/i_util.h"
#include "modules/perception/common/i_lib/geometry/i_line.h"
...
...
modules/perception/camera/common/undistortion_handler.h
浏览文件 @
8047dffb
...
...
@@ -21,8 +21,8 @@
#include <string>
#include "modules/perception/base/blob.h"
#include "modules/perception/base/image.h"
#include "modules/perception/base/distortion_model.h"
#include "modules/perception/base/image.h"
#include "modules/perception/common/sensor_manager/sensor_manager.h"
namespace
apollo
{
...
...
modules/perception/camera/common/util.h
浏览文件 @
8047dffb
...
...
@@ -21,19 +21,19 @@
#include <google/protobuf/io/gzip_stream.h>
#include <google/protobuf/text_format.h>
#include <cblas.h>
#include <string>
#include <vector>
#include <map>
#include <algorithm>
#include <numeric>
#include <memory>
#include <iostream>
#include <fstream>
#include <iostream>
#include <map>
#include <memory>
#include <numeric>
#include <string>
#include <vector>
#include "glog/logging.h"
#include "modules/perception/base/blob.h"
#include "modules/perception/base/image.h"
#include "modules/perception/base/object.h"
#include "modules/perception/base/object_types.h"
#include "modules/perception/base/image.h"
#include "glog/logging.h"
namespace
apollo
{
namespace
perception
{
...
...
modules/perception/camera/lib/calibration_service/online_calibration_service/BUILD
浏览文件 @
8047dffb
...
...
@@ -12,9 +12,9 @@ cc_library(
"online_calibration_service.h"
,
],
deps
=
[
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/common/i_lib/core:core"
,
"//modules/perception/common/i_lib/geometry:i_plane"
,
"//modules/perception/camera/lib/interface:interface"
,
],
)
...
...
modules/perception/camera/lib/calibrator/laneline/BUILD
浏览文件 @
8047dffb
...
...
@@ -46,6 +46,4 @@ cc_library(
],
)
cpplint
()
modules/perception/camera/lib/calibrator/laneline/laneline_calibrator.cc
浏览文件 @
8047dffb
...
...
@@ -104,7 +104,7 @@ bool LaneLineCalibrator::LoadEgoLaneline(
bool
found_ego_left
=
false
;
bool
found_ego_right
=
false
;
// using points from model fitting
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
lane_objects
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
lane_objects
.
size
(
);
++
i
)
{
if
(
lane_objects
[
i
].
pos_type
==
base
::
LaneLinePositionType
::
EGO_LEFT
)
{
int
num_points
=
lane_objects
[
i
].
curve_image_point_set
.
size
();
...
...
modules/perception/camera/lib/feature_extractor/tfe/BUILD
浏览文件 @
8047dffb
...
...
@@ -28,12 +28,14 @@ cc_library(
],
deps
=
[
":tracking_feature_proto"
,
"//modules/common/util:file_util"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/inference:inference_lib"
,
"//modules/perception/inference:inference_factory_lib"
,
"//modules/perception/inference
/utils:inference_util
_lib"
,
"//modules/perception/inference
:inference
_lib"
,
"//modules/perception/inference/utils:inference_resize_lib"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/lib/io:file_util"
,
],
)
...
...
@@ -49,7 +51,7 @@ cc_library(
deps
=
[
":tracking_feature_proto"
,
"//modules/perception/lib/io:file_util"
,
"//modules/
perception/lib/io:protobuf
_util"
,
"//modules/
common/util:file
_util"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/inference:inference_factory_lib"
,
...
...
@@ -76,7 +78,7 @@ cc_library(
"//modules/perception/inference/utils:inference_gemm_lib"
,
"//modules/perception/inference/operators:perception_inference_operators"
,
"//modules/perception/lib/io:file_util"
,
"//modules/
perception/lib/io:protobuf
_util"
,
"//modules/
common/util:file
_util"
,
],
)
...
...
modules/perception/camera/lib/feature_extractor/tfe/external_feature_extractor.cc
浏览文件 @
8047dffb
...
...
@@ -14,10 +14,12 @@
* limitations under the License.
*****************************************************************************/
#include "modules/perception/camera/lib/feature_extractor/tfe/external_feature_extractor.h"
#include <vector>
#include <map>
#include <vector>
#include "modules/common/util/file.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/camera/common/global_config.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/inference/inference_factory.h"
...
...
@@ -31,8 +33,8 @@ bool ExternalFeatureExtractor::Init(const FeatureExtractorInitOptions
&
options
)
{
std
::
string
efx_config
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
CHECK
(
lib
::
ParseProtobufFromFile
<
tracking_feature
::
ExternalParam
>
(
efx_config
,
&
param_
))
CHECK
(
apollo
::
common
::
util
::
GetProtoFromFile
<
tracking_feature
::
ExternalParam
>
(
efx_config
,
&
param_
))
<<
"Read config failed: "
<<
efx_config
;
AINFO
<<
"Load config Success: "
<<
param_
.
ShortDebugString
();
std
::
string
proto_file
=
...
...
modules/perception/camera/lib/feature_extractor/tfe/project_feature.cc
浏览文件 @
8047dffb
...
...
@@ -19,11 +19,11 @@
#include <vector>
#include "cybertron/common/log.h"
#include "modules/common/util/file.h"
#include "modules/perception/camera/common/global_config.h"
#include "modules/perception/inference/inference_factory.h"
#include "modules/perception/inference/utils/gemm.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/lib/singleton/singleton.h"
namespace
apollo
{
...
...
@@ -33,8 +33,8 @@ namespace camera {
bool
ProjectFeature
::
Init
(
const
FeatureExtractorInitOptions
&
options
)
{
std
::
string
efx_config
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
CHECK
(
lib
::
ParseProtobufFromFile
<
tracking_feature
::
ExternalParam
>
(
efx_config
,
&
param_
))
CHECK
(
apollo
::
common
::
util
::
GetProtoFromFile
<
tracking_feature
::
ExternalParam
>
(
efx_config
,
&
param_
))
<<
"Read config failed: "
<<
efx_config
;
AINFO
<<
"Load config Success: "
<<
param_
.
ShortDebugString
();
std
::
string
proto_file
=
...
...
modules/perception/camera/lib/feature_extractor/tfe/tracking_feat_extractor.cc
浏览文件 @
8047dffb
...
...
@@ -16,9 +16,9 @@
#include <iostream>
#include <fstream>
#include "modules/common/util/file.h"
#include "modules/perception/camera/lib/feature_extractor/tfe/tracking_feat_extractor.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -36,7 +36,7 @@ bool TrackingFeatureExtractor::Init(const FeatureExtractorInitOptions
std
::
string
config_path
=
lib
::
FileUtil
::
GetAbsolutePath
(
init_options
.
root_dir
,
init_options
.
conf_file
);
if
(
!
lib
::
ParseProtobuf
FromFile
(
config_path
,
&
feat_param
))
{
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
config_path
,
&
feat_param
))
{
AERROR
<<
"read proto_config fail"
;
return
false
;
}
...
...
modules/perception/camera/lib/interface/BUILD
浏览文件 @
8047dffb
...
...
@@ -69,8 +69,6 @@ cc_library(
hdrs
=
[
"base_obstacle_postprocessor.h"
,
],
deps
=
[
],
)
cc_library
(
...
...
@@ -228,5 +226,4 @@ cc_library(
],
)
cpplint
()
modules/perception/camera/lib/lane/detector/denseline/BUILD
浏览文件 @
8047dffb
...
...
@@ -13,17 +13,17 @@ cc_library(
"denseline_lane_detector.h"
,
],
deps
=
[
"//modules/common/util:file_util"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/lane/common:denseline_proto"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/camera/lib/lane/common:denseline_proto"
,
"//modules/perception/inference:inference_factory_lib"
,
"//modules/perception/inference/tensorrt:rt_net"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/inference/utils:inference_resize_lib"
,
"//modules/perception/
lib/registerer:registerer
"
,
"//modules/perception/
inference/utils:inference_util_lib
"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/
io:protobuf_util
"
,
"//modules/perception/lib/
registerer:registerer
"
,
],
)
...
...
modules/perception/camera/lib/lane/detector/denseline/denseline_lane_detector.cc
浏览文件 @
8047dffb
...
...
@@ -18,7 +18,7 @@
#include <map>
#include <algorithm>
#include "modules/
perception/lib/io/protobuf_util
.h"
#include "modules/
common/util/file
.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/inference/utils/resize.h"
...
...
@@ -31,7 +31,7 @@ namespace camera {
bool
DenselineLaneDetector
::
Init
(
const
LaneDetectorInitOptions
&
options
)
{
std
::
string
proto_path
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
if
(
!
lib
::
ParseProtobuf
FromFile
(
proto_path
,
&
denseline_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
proto_path
,
&
denseline_param_
))
{
AINFO
<<
"load proto param failed, root dir: "
<<
options
.
root_dir
;
return
false
;
}
...
...
modules/perception/camera/lib/lane/postprocessor/denseline/BUILD
浏览文件 @
8047dffb
...
...
@@ -30,14 +30,14 @@ cc_library(
deps
=
[
"//cybertron"
,
":denseline_postprocessor_proto"
,
"//modules/common/util:file_util"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/camera/lib/lane/common:denseline_proto"
,
"//modules/perception/camera/lib/lane/common:common_functions"
,
"//modules/perception/
lib/registerer:registerer
"
,
"//modules/perception/
camera/lib/lane/common:denseline_proto
"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/
io:protobuf_util
"
,
"//modules/perception/lib/
registerer:registerer
"
,
"//modules/perception/lib/singleton:singleton"
,
"//modules/perception/lib/utils:utils"
,
],
...
...
modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.cc
浏览文件 @
8047dffb
...
...
@@ -20,12 +20,12 @@
#include <iostream>
#include "cybertron/common/log.h"
#include "modules/common/util/file.h"
#include "modules/perception/base/object_types.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/camera/lib/lane/common/denseline.pb.h"
#include "modules/perception/camera/common/math_functions.h"
#include "modules/perception/camera/lib/lane/common/denseline.pb.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/lib/utils/timer.h"
namespace
apollo
{
...
...
@@ -39,7 +39,7 @@ bool DenselineLanePostprocessor::Init(
const
std
::
string
&
proto_path
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
detect_config_root
,
options
.
detect_config_name
);
if
(
!
lib
::
ParseProtobuf
FromFile
(
proto_path
,
&
denseline_param
))
{
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
proto_path
,
&
denseline_param
))
{
AINFO
<<
"load proto param failed, root dir: "
<<
options
.
root_dir
;
return
false
;
}
...
...
@@ -58,7 +58,7 @@ bool DenselineLanePostprocessor::Init(
const
std
::
string
&
postprocessor_config
=
lib
::
FileUtil
::
GetAbsolutePath
(
root_dir
,
conf_file
);
AINFO
<<
"postprocessor_config:"
<<
postprocessor_config
;
if
(
!
lib
::
ParseProtobuf
FromFile
(
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
postprocessor_config
,
&
lane_postprocessor_param_
))
{
AERROR
<<
"Read config detect_param failed: "
<<
postprocessor_config
;
return
false
;
...
...
modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.h
浏览文件 @
8047dffb
...
...
@@ -93,7 +93,7 @@ class DenselineLanePostprocessor : public BaseLanePostprocessor {
static
bool
CompareCCSize
(
const
ConnectedComponent
&
cc1
,
const
ConnectedComponent
&
cc2
)
{
std
::
vector
<
base
::
Point2DI
>
cc1_pixels
=
cc1
.
GetPixels
();
std
::
vector
<
base
::
Point2DI
>
cc2_pixels
=
cc
1
.
GetPixels
();
std
::
vector
<
base
::
Point2DI
>
cc2_pixels
=
cc
2
.
GetPixels
();
return
cc1_pixels
.
size
()
>
cc2_pixels
.
size
();
}
// @brief: infer point set from lane center
...
...
modules/perception/camera/lib/obstacle/detector/yolo/BUILD
浏览文件 @
8047dffb
...
...
@@ -51,19 +51,19 @@ cc_library(
],
deps
=
[
":region_output"
,
"//modules/common/util:file_util"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/camera/lib/feature_extractor/tfe:external_feature_extractor"
,
"//modules/perception/camera/lib/feature_extractor/tfe:project_feature"
,
"//modules/perception/camera/lib/feature_extractor/tfe:tracking_feat_extractor"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/camera/lib/obstacle/detector/yolo/proto:yolo_proto"
,
"//modules/perception/inference:inference_lib"
,
"//modules/perception/inference:inference_factory_lib"
,
"//modules/perception/inference
/utils:inference_util
_lib"
,
"//modules/perception/inference
:inference
_lib"
,
"//modules/perception/inference/utils:inference_resize_lib"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
"//modules/perception/lib/utils:utils"
,
],
)
...
...
modules/perception/camera/lib/obstacle/detector/yolo/region_output.cu
浏览文件 @
8047dffb
...
...
@@ -525,7 +525,7 @@ void get_objects_gpu(const YoloBlobs &yolo_blobs,
overlapped
,
idx_sm
,
stream
);
for
(
int
k
=
0
;
k
<
num_classes
;
k
++
)
{
for
(
int
k
=
0
;
k
<
num_classes
;
++
k
)
{
apply_nms_gpu
(
res_box_data
,
cpu_cls_data
+
k
*
num_candidates
,
rest_indices
,
...
...
@@ -562,7 +562,7 @@ void get_objects_gpu(const YoloBlobs &yolo_blobs,
}
const
std
::
vector
<
float
>
&
scores
=
conf_scores
.
find
(
label
)
->
second
;
std
::
vector
<
int
>
&
indice
=
it
->
second
;
for
(
int
j
=
0
;
j
<
static_cast
<
int
>
(
indice
.
size
()
);
++
j
)
{
for
(
size_t
j
=
0
;
j
<
indice
.
size
(
);
++
j
)
{
int
idx
=
indice
[
j
];
const
float
*
bbox
=
cpu_box_data
+
idx
*
kBoxBlockSize
;
if
(
scores
[
idx
]
<
model_param
.
confidence_threshold
())
{
...
...
@@ -662,7 +662,7 @@ void get_max_score_index(const std::vector<float> &scores,
const
int
top_k
,
std
::
vector
<
std
::
pair
<
float
,
int
>
>
*
score_index_vec
)
{
// Generate index score pairs.
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
scores
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
scores
.
size
(
);
++
i
)
{
if
(
scores
[
i
]
>
threshold
)
{
score_index_vec
->
push_back
(
std
::
make_pair
(
scores
[
i
],
i
));
}
...
...
@@ -731,16 +731,16 @@ void apply_boxvoting_fast(std::vector<NormalizedBBox> *bboxes,
return
;
}
indices
->
clear
();
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
bboxes
->
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
bboxes
->
size
();
++
i
)
{
(
*
bboxes
)[
i
].
mask
=
false
;
if
((
*
scores
)[
i
]
>
conf_threshold
)
{
indices
->
push_back
(
i
);
}
}
for
(
int
count
=
0
;
count
<
static_cast
<
int
>
(
indices
->
size
());
count
++
)
{
for
(
size_t
count
=
0
;
count
<
indices
->
size
();
++
count
)
{
int
max_box_idx
=
0
;
for
(
int
i
=
1
;
i
<
static_cast
<
int
>
(
indices
->
size
());
i
++
)
{
for
(
size_t
i
=
1
;
i
<
indices
->
size
();
++
i
)
{
int
idx
=
indices
->
at
(
i
);
if
((
*
bboxes
)[
idx
].
mask
)
{
continue
;
...
...
@@ -758,7 +758,7 @@ void apply_boxvoting_fast(std::vector<NormalizedBBox> *bboxes,
float
x2_vt
=
best_bbox
.
xmax
*
s_vt
;
float
y1_vt
=
best_bbox
.
ymin
*
s_vt
;
float
y2_vt
=
best_bbox
.
ymax
*
s_vt
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
indices
->
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
indices
->
size
();
++
i
)
{
int
sub_it
=
indices
->
at
(
i
);
if
((
*
bboxes
)[
sub_it
].
mask
)
{
continue
;
...
...
@@ -812,7 +812,7 @@ void apply_nms_fast(const std::vector<NormalizedBBox> &bboxes,
while
(
score_index_vec
.
size
()
!=
0
)
{
const
int
idx
=
score_index_vec
.
front
().
second
;
bool
keep
=
true
;
for
(
int
k
=
0
;
k
<
static_cast
<
int
>
(
indices
->
size
()
);
++
k
)
{
for
(
size_t
k
=
0
;
k
<
indices
->
size
(
);
++
k
)
{
if
(
keep
)
{
const
int
kept_idx
=
(
*
indices
)[
k
];
float
overlap
=
get_jaccard_overlap
(
bboxes
[
idx
],
bboxes
[
kept_idx
]);
...
...
@@ -833,9 +833,9 @@ void apply_nms_fast(const std::vector<NormalizedBBox> &bboxes,
void
filter_bbox
(
const
MinDims
&
min_dims
,
std
::
vector
<
base
::
ObjectPtr
>
*
objects
)
{
in
t
valid_obj_idx
=
0
;
in
t
total_obj_idx
=
0
;
while
(
total_obj_idx
<
static_cast
<
int
>
(
objects
->
size
()
))
{
size_
t
valid_obj_idx
=
0
;
size_
t
total_obj_idx
=
0
;
while
(
total_obj_idx
<
objects
->
size
(
))
{
const
auto
&
obj
=
(
*
objects
)[
total_obj_idx
];
if
((
obj
->
camera_supplement
.
box
.
ymax
-
obj
->
camera_supplement
.
box
.
ymin
)
>=
min_dims
.
min_2d_height
&&
...
...
@@ -968,7 +968,7 @@ void fill_area_id(bool with_flag, base::ObjectPtr obj, const float *data) {
int
get_area_id
(
float
visible_ratios
[
4
])
{
int
area_id
=
0
;
int
max_face
=
0
;
for
(
int
i
=
1
;
i
<
4
;
i
++
)
{
for
(
int
i
=
1
;
i
<
4
;
++
i
)
{
if
(
visible_ratios
[
i
]
>
visible_ratios
[
max_face
])
{
max_face
=
i
;
}
...
...
modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.cc
浏览文件 @
8047dffb
...
...
@@ -17,9 +17,9 @@
#include "cybertron/common/log.h"
#include "modules/perception/base/common.h"
#include "modules/perception/camera/common/timer.h"
#include "modules/perception/lib/utils/perf.h"
#include "modules/perception/inference/utils/resize.h"
#include "modules/perception/inference/inference_factory.h"
#include "modules/perception/inference/utils/resize.h"
#include "modules/perception/lib/utils/perf.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -197,7 +197,7 @@ bool YoloObstacleDetector::Init(const ObstacleDetectorInitOptions &options) {
CHECK
(
base_camera_model_
!=
nullptr
)
<<
"base_camera_model is nullptr!"
;
std
::
string
config_path
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
if
(
!
lib
::
ParseProtobuf
FromFile
(
config_path
,
&
yolo_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
config_path
,
&
yolo_param_
))
{
AERROR
<<
"read proto_config fail"
;
return
false
;
}
...
...
modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.h
浏览文件 @
8047dffb
...
...
@@ -15,22 +15,23 @@
*****************************************************************************/
#pragma once
#include <string>
#include <map>
#include <vector>
#include <memory>
#include "modules/perception/base/object_types.h"
#include <string>
#include <vector>
#include "modules/common/util/file.h"
#include "modules/perception/base/box.h"
#include "modules/perception/inference/inference.h"
#include "modules/perception/inference/utils/resize.h"
#include "modules/perception/inference/utils/util.h"
#include "modules/perception/base/object_types.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/camera/lib/interface/base_feature_extractor.h"
#include "modules/perception/camera/lib/interface/base_obstacle_detector.h"
#include "modules/perception/camera/lib/obstacle/detector/yolo/proto/yolo.pb.h"
#include "modules/perception/camera/lib/obstacle/detector/yolo/region_output.h"
#include "modules/perception/camera/lib/interface/base_obstacle_detector.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/inference/inference.h"
#include "modules/perception/inference/utils/resize.h"
#include "modules/perception/inference/utils/util.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/camera/lib/interface/base_feature_extractor.h"
namespace
apollo
{
namespace
perception
{
...
...
modules/perception/camera/lib/obstacle/postprocessor/location_refiner/BUILD
浏览文件 @
8047dffb
...
...
@@ -30,11 +30,11 @@ cc_library(
":obj_postprocessor"
,
":location_refiner_proto"
,
"//cybertron"
,
"//modules/common/util:file_util"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/lib/singleton:singleton"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/
io:protobuf_util
"
,
"//modules/perception/lib/
singleton:singleton
"
,
],
)
...
...
modules/perception/camera/lib/obstacle/postprocessor/location_refiner/location_refiner_obstacle_postprocessor.cc
浏览文件 @
8047dffb
...
...
@@ -19,11 +19,11 @@
#include <algorithm>
#include "cybertron/common/log.h"
#include "modules/common/util/file.h"
#include "modules/perception/camera/common/global_config.h"
#include "modules/perception/camera/lib/interface/base_calibration_service.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/
io/protobuf_util
.h"
#include "modules/perception/lib/
singleton/singleton
.h"
// TODO(Xun): code completion
...
...
@@ -36,9 +36,9 @@ bool LocationRefinerObstaclePostprocessor::Init(
std
::
string
postprocessor_config
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
if
(
!
lib
::
ParseProtobufFromFile
<
location_refiner
::
LocationRefinerParam
>
(
postprocessor_config
,
&
location_refiner_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProtoFromFile
<
location_refiner
::
LocationRefinerParam
>
(
postprocessor_config
,
&
location_refiner_param_
))
{
AERROR
<<
"Read config failed: "
<<
postprocessor_config
;
return
false
;
}
...
...
modules/perception/camera/lib/obstacle/tracker/common/kalman_filter.cc
浏览文件 @
8047dffb
...
...
@@ -219,7 +219,7 @@ void MaxNMeanFilter::AddMeasure(const Eigen::VectorXd &z) {
Eigen
::
VectorXd
MaxNMeanFilter
::
get_state
()
const
{
Eigen
::
VectorXd
x
=
measures_
[
0
];
for
(
unsigned
in
t
i
=
1
;
i
<
measures_
.
size
();
++
i
)
{
for
(
size_
t
i
=
1
;
i
<
measures_
.
size
();
++
i
)
{
x
+=
measures_
[
i
];
}
x
=
x
/
measures_
.
size
();
...
...
modules/perception/camera/lib/obstacle/tracker/common/similar.cc
浏览文件 @
8047dffb
...
...
@@ -35,7 +35,7 @@ bool CosineSimilar::Calc(CameraFrame *frame1,
for
(
auto
&
object1
:
frame1
->
detected_objects
)
{
for
(
auto
&
object2
:
frame2
->
detected_objects
)
{
float
s
=
0
;
for
(
int
k
=
0
;
k
<
static_cast
<
int
>
(
dim
)
;
++
k
)
{
for
(
size_t
k
=
0
;
k
<
dim
;
++
k
)
{
s
+=
object1
->
camera_supplement
.
object_feature
[
k
]
*
object2
->
camera_supplement
.
object_feature
[
k
];
}
...
...
modules/perception/camera/lib/obstacle/tracker/omt/BUILD
浏览文件 @
8047dffb
...
...
@@ -18,7 +18,6 @@ proto_library(
)
cc_library
(
name
=
"track_object"
,
srcs
=
[
...
...
@@ -30,8 +29,8 @@ cc_library(
deps
=
[
":frame_list"
,
"//modules/perception/base:base"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/inference/utils:inference_cuda_util_lib"
,
"//modules/perception/inference/utils:inference_util_lib"
,
],
)
...
...
@@ -62,8 +61,8 @@ cc_library(
"//cybertron"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/inference/utils:inference_cuda_util_lib"
,
"//modules/perception/inference/utils:inference_util_lib"
,
],
)
...
...
@@ -80,9 +79,11 @@ cc_library(
":obstacle_reference"
,
":omt_proto"
,
":target"
,
"//modules/common/util:file_util"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/camera/lib/obstacle/tracker/common:common"
,
"//modules/perception/lib/io:file_util"
,
],
)
...
...
modules/perception/camera/lib/obstacle/tracker/omt/obstacle_reference.cc
浏览文件 @
8047dffb
...
...
@@ -246,7 +246,7 @@ void ObstacleReference::CorrectSize(CameraFrame *frame) {
std
::
vector
<
float
>
height_error
(
kTemplateHWL
.
size
(),
0
);
float
obj_h
=
obj
->
size
[
2
];
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
height_error
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
height_error
.
size
(
);
++
i
)
{
height_error
[
i
]
=
std
::
abs
(
kTemplateHWL
[
i
].
at
(
obj
->
sub_type
).
at
(
0
)
-
obj_h
);
}
...
...
modules/perception/camera/lib/obstacle/tracker/omt/omt_obstacle_tracker.cc
浏览文件 @
8047dffb
...
...
@@ -19,19 +19,20 @@
#include <google/protobuf/io/gzip_stream.h>
#include <fcntl.h>
#include <vector>
#include <algorithm>
#include <functional>
#include <string>
#include <map>
#include <string>
#include <vector>
#include "modules/common/util/file.h"
#include "modules/perception/base/point.h"
#include "modules/perception/camera/common/global_config.h"
#include "modules/perception/camera/common/math_functions.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/common/geometry/common.h"
#include "modules/perception/camera/common/global_config.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/base/point.h"
#include "modules/perception/camera/common/math_functions.h"
#include "modules/perception/lib/singleton/singleton.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -40,7 +41,8 @@ namespace camera {
bool
OMTObstacleTracker
::
Init
(
const
ObstacleTrackerInitOptions
&
options
)
{
std
::
string
omt_config
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
if
(
!
lib
::
ParseProtobufFromFile
<
omt
::
OmtParam
>
(
omt_config
,
&
omt_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProtoFromFile
<
omt
::
OmtParam
>
(
omt_config
,
&
omt_param_
))
{
AERROR
<<
"Read config failed: "
<<
omt_config
;
return
false
;
}
...
...
@@ -91,11 +93,11 @@ std::string OMTObstacleTracker::Name() const {
bool
OMTObstacleTracker
::
CombineDuplicateTargets
()
{
std
::
vector
<
Hypothesis
>
score_list
;
Hypothesis
hypo
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
targets_
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
targets_
.
size
(
);
++
i
)
{
if
(
targets_
[
i
].
Size
()
==
0
)
{
continue
;
}
for
(
int
j
=
i
+
1
;
j
<
static_cast
<
int
>
(
targets_
.
size
()
);
++
j
)
{
for
(
size_t
j
=
i
+
1
;
j
<
targets_
.
size
(
);
++
j
)
{
if
(
targets_
[
j
].
Size
()
==
0
)
{
continue
;
}
...
...
@@ -182,9 +184,9 @@ bool OMTObstacleTracker::CombineDuplicateTargets() {
void
OMTObstacleTracker
::
GenerateHypothesis
(
const
TrackObjectPtrs
&
objects
)
{
std
::
vector
<
Hypothesis
>
score_list
;
Hypothesis
hypo
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
targets_
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
targets_
.
size
(
);
++
i
)
{
ADEBUG
<<
"Target "
<<
targets_
[
i
].
id
;
for
(
int
j
=
0
;
j
<
static_cast
<
int
>
(
objects
.
size
()
);
++
j
)
{
for
(
size_t
j
=
0
;
j
<
objects
.
size
(
);
++
j
)
{
hypo
.
target
=
i
;
hypo
.
object
=
j
;
float
sa
=
ScoreAppearance
(
targets_
[
i
],
objects
[
j
]);
...
...
@@ -337,7 +339,7 @@ int OMTObstacleTracker::CreateNewTarget(const TrackObjectPtrs &objects) {
target_rects
.
push_back
(
target_rect
);
}
int
created_count
=
0
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
objects
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
objects
.
size
(
);
++
i
)
{
if
(
!
used_
[
i
])
{
bool
is_covered
=
false
;
const
auto
&
sub_type
=
objects
[
i
]
->
object
->
sub_type
;
...
...
@@ -387,7 +389,7 @@ bool OMTObstacleTracker::Associate2D(const ObstacleTrackerOptions &options,
}
TrackObjectPtrs
track_objects
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
frame
->
detected_objects
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
frame
->
detected_objects
.
size
(
);
++
i
)
{
// TODO(gaohan): use pool
TrackObjectPtr
track_ptr
(
new
TrackObject
);
track_ptr
->
object
=
frame
->
detected_objects
[
i
];
...
...
modules/perception/camera/lib/obstacle/tracker/omt/target.cc
浏览文件 @
8047dffb
...
...
@@ -62,8 +62,8 @@ void Target::Add(TrackObjectPtr object) {
tracked_objects
.
push_back
(
object
);
}
void
Target
::
RemoveOld
(
int
frame_id
)
{
in
t
index
=
0
;
while
(
index
<
static_cast
<
int
>
(
tracked_objects
.
size
()
)
&&
size_
t
index
=
0
;
while
(
index
<
tracked_objects
.
size
(
)
&&
tracked_objects
[
index
]
->
indicator
.
frame_id
<
frame_id
)
{
++
index
;
}
...
...
modules/perception/camera/lib/obstacle/transformer/multicue/BUILD
浏览文件 @
8047dffb
...
...
@@ -44,10 +44,10 @@ cc_library(
":multicue_proto"
,
":obj_mapper"
,
"//cybertron"
,
"//modules/
perception/camera/lib/interface:interface
"
,
"//modules/
common/util:file_util
"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
"//modules/perception/lib/singleton:singleton"
,
],
)
...
...
modules/perception/camera/lib/obstacle/transformer/multicue/multicue_obstacle_transformer.cc
浏览文件 @
8047dffb
...
...
@@ -16,9 +16,9 @@
#include "modules/perception/camera/lib/obstacle/transformer/multicue/multicue_obstacle_transformer.h"
#include "cybertron/common/log.h"
#include "modules/common/util/file.h"
#include "modules/perception/camera/common/global_config.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/lib/singleton/singleton.h"
namespace
apollo
{
...
...
@@ -30,8 +30,8 @@ bool MultiCueObstacleTransformer::Init(
std
::
string
transformer_config
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
if
(
!
lib
::
ParseProtobufFromFile
<
multicue
::
MulticueParam
>
(
transformer_config
,
&
multicue_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProtoFromFile
<
multicue
::
MulticueParam
>
(
transformer_config
,
&
multicue_param_
))
{
AERROR
<<
"Read config failed: "
<<
transformer_config
;
return
false
;
}
...
...
modules/perception/camera/lib/traffic_light/detector/detection/BUILD
浏览文件 @
8047dffb
...
...
@@ -30,15 +30,15 @@ cc_library(
":select"
,
":trafficlight_detector_detection_proto"
,
"//cybertron"
,
"//modules/common/util:file_util"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
"//modules/perception/inference:inference_lib"
,
"//modules/perception/inference:inference_factory_lib"
,
"//modules/perception/inference
/utils:inference_util
_lib"
,
"//modules/perception/inference
:inference
_lib"
,
"//modules/perception/inference/utils:inference_resize_lib"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/lib/io:file_util"
,
],
)
...
...
modules/perception/camera/lib/traffic_light/detector/detection/detection.cc
浏览文件 @
8047dffb
...
...
@@ -22,8 +22,8 @@
#include <numeric>
#include "cybertron/common/log.h"
#include "modules/common/util/file.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/inference/utils/util.h"
#include "modules/perception/inference/utils/resize.h"
...
...
@@ -37,7 +37,7 @@ bool TrafficLightDetection::Init(
std
::
string
proto_path
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
AINFO
<<
"proto_path "
<<
proto_path
;
if
(
!
lib
::
ParseProtobuf
FromFile
(
proto_path
,
&
detection_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
proto_path
,
&
detection_param_
))
{
AINFO
<<
"load proto param failed, root dir: "
<<
options
.
root_dir
;
return
false
;
}
...
...
@@ -183,7 +183,7 @@ TrafficLightDetection::Inference(std::vector<base::TrafficLightPtr> *lights,
detection_param_
.
min_crop_size
(),
3
);
param_blob_
->
Reshape
(
batch_num
,
6
,
1
,
1
);
float
*
param_data
=
param_blob_
->
mutable_cpu_data
();
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
batch_num
)
;
++
i
)
{
for
(
size_t
i
=
0
;
i
<
batch_num
;
++
i
)
{
auto
offset
=
i
*
param_blob_length_
;
param_data
[
offset
+
0
]
=
detection_param_
.
min_crop_size
();
param_data
[
offset
+
1
]
=
detection_param_
.
min_crop_size
();
...
...
@@ -195,7 +195,7 @@ TrafficLightDetection::Inference(std::vector<base::TrafficLightPtr> *lights,
AINFO
<<
"reshape inputblob "
<<
input_img_blob
->
shape_string
();
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
batch_num
)
;
++
i
)
{
for
(
size_t
i
=
0
;
i
<
batch_num
;
++
i
)
{
base
::
TrafficLightPtr
light
=
lights
->
at
(
i
);
base
::
RectI
cbox
;
crop_
->
getCropBox
(
img_width
,
img_height
,
light
,
&
cbox
);
...
...
@@ -283,7 +283,7 @@ bool TrafficLightDetection::Detect(
AINFO
<<
"Dump output Done! Get box num:"
<<
detected_bboxes_
.
size
();
for
(
int
j
=
0
;
j
<
static_cast
<
int
>
(
detected_bboxes_
.
size
()
);
++
j
)
{
for
(
size_t
j
=
0
;
j
<
detected_bboxes_
.
size
(
);
++
j
)
{
base
::
RectI
&
region
=
detected_bboxes_
[
j
]
->
region
.
detection_roi
;
float
score
=
detected_bboxes_
[
j
]
->
region
.
detect_score
;
lights_ref
[
0
]
->
region
.
debug_roi
.
push_back
(
region
);
...
...
modules/perception/camera/lib/traffic_light/detector/detection/select.cc
浏览文件 @
8047dffb
...
...
@@ -46,16 +46,16 @@ void Select::SelectTrafficLights(
std
::
vector
<
std
::
pair
<
size_t
,
size_t
>
>
assignments
;
munkres_
.
costs
()
->
Resize
(
hdmap_bboxes
->
size
(),
refined_bboxes
.
size
());
for
(
int
row
=
0
;
row
<
static_cast
<
int
>
(
hdmap_bboxes
->
size
()
);
++
row
)
{
for
(
size_t
row
=
0
;
row
<
hdmap_bboxes
->
size
(
);
++
row
)
{
auto
center_hd
=
(
*
hdmap_bboxes
)[
row
]
->
region
.
detection_roi
.
Center
();
if
((
*
hdmap_bboxes
)[
row
]
->
region
.
outside_image
)
{
AINFO
<<
"projection_roi outside image, set score to 0."
;
for
(
int
col
=
0
;
col
<
static_cast
<
int
>
(
refined_bboxes
.
size
()
);
++
col
)
{
for
(
size_t
col
=
0
;
col
<
refined_bboxes
.
size
(
);
++
col
)
{
(
*
munkres_
.
costs
())(
row
,
col
)
=
0.0
;
}
continue
;
}
for
(
int
col
=
0
;
col
<
static_cast
<
int
>
(
refined_bboxes
.
size
()
);
++
col
)
{
for
(
size_t
col
=
0
;
col
<
refined_bboxes
.
size
(
);
++
col
)
{
float
gaussian_score
=
100.0
f
;
auto
center_refine
=
refined_bboxes
[
col
]
->
region
.
detection_roi
.
Center
();
// use gaussian score as metrics of distance and width
...
...
modules/perception/camera/lib/traffic_light/detector/recognition/BUILD
浏览文件 @
8047dffb
...
...
@@ -26,14 +26,14 @@ cc_library(
],
deps
=
[
":trafficlight_detector_recognition_proto"
,
"//modules/perception/
camera/lib/interface:interfac
e"
,
"//modules/perception/
base:bas
e"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/
inference:inference_lib
"
,
"//modules/perception/
camera/lib/interface:interface
"
,
"//modules/perception/inference:inference_factory_lib"
,
"//modules/perception/base:base"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/inference:inference_lib"
,
"//modules/perception/inference/utils:inference_resize_lib"
,
"//modules/perception/inference/utils:inference_util_lib"
,
"//modules/perception/lib/io:file_util"
,
],
)
...
...
@@ -51,7 +51,7 @@ cc_library(
"//modules/perception/inference:inference_lib"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/lib/io:file_util"
,
"//modules/
perception/lib/io:protobuf
_util"
,
"//modules/
common/util:file
_util"
,
],
)
...
...
modules/perception/camera/lib/traffic_light/detector/recognition/classify.cc
浏览文件 @
8047dffb
...
...
@@ -171,7 +171,7 @@ void ClassifyBySimple::Prob2Color(const float *out_put_data, float threshold,
light
->
status
.
confidence
=
out_put_data
[
max_color_id
];
AINFO
<<
"Light status recognized as "
<<
name_map
[
max_color_id
];
AINFO
<<
"Color Prob:"
;
for
(
int
j
=
0
;
j
<
static_cast
<
int
>
(
status_map
.
size
()
);
j
++
)
{
for
(
size_t
j
=
0
;
j
<
status_map
.
size
(
);
j
++
)
{
AINFO
<<
out_put_data
[
j
];
}
}
...
...
modules/perception/camera/lib/traffic_light/detector/recognition/recognition.cc
浏览文件 @
8047dffb
...
...
@@ -17,8 +17,8 @@
#include <string>
#include "modules/common/util/file.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -30,7 +30,7 @@ TrafficLightRecognition::Init(const TrafficLightDetectorInitOptions& options) {
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
AINFO
<<
"proto_path "
<<
proto_path
;
if
(
!
lib
::
ParseProtobuf
FromFile
(
proto_path
,
&
recognize_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
proto_path
,
&
recognize_param_
))
{
AINFO
<<
"load proto param failed, root dir: "
<<
options
.
root_dir
;
return
false
;
}
...
...
modules/perception/camera/lib/traffic_light/preprocessor/BUILD
浏览文件 @
8047dffb
...
...
@@ -18,7 +18,6 @@ proto_library(
)
cc_library
(
name
=
"multi_camera_projection"
,
srcs
=
[
...
...
@@ -30,12 +29,12 @@ cc_library(
deps
=
[
":pose"
,
"//cybertron"
,
"//modules/common/util:file_util"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/common/sensor_manager:sensor_manager"
,
"//modules/perception/common/io:io_util"
,
"//modules/perception/common/sensor_manager:sensor_manager"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
],
)
...
...
@@ -78,7 +77,7 @@ cc_library(
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/lib/utils:utils"
,
"//modules/perception/lib/io:file_util"
,
"//modules/
perception/lib/io:protobuf
_util"
,
"//modules/
common/util:file
_util"
,
"//modules/perception/lib/config_manager:config_manager"
,
"//modules/perception/camera/lib/interface:base_init_options"
,
],
...
...
modules/perception/camera/lib/traffic_light/preprocessor/multi_camera_projection.cc
浏览文件 @
8047dffb
...
...
@@ -18,15 +18,15 @@
#include <gflags/gflags.h>
#include <boost/function.hpp>
#include <boost/bind.hpp>
#include <string>
#include <algorithm>
#include <numeric>
#include <limits>
#include <cmath>
#include <limits>
#include <numeric>
#include <string>
#include "cybertron/common/log.h"
#include "modules/common/util/file.h"
#include "modules/perception/common/sensor_manager/sensor_manager.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/common/io/io_util.h"
#include "modules/perception/camera/common/util.h"
...
...
modules/perception/camera/lib/traffic_light/preprocessor/tl_preprocessor.cc
浏览文件 @
8047dffb
...
...
@@ -18,11 +18,11 @@
#include <gflags/gflags.h>
#include "cybertron/common/log.h"
#include "modules/common/util/file.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/lib/config_manager/config_manager.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/lib/utils/time_util.h"
#include "modules/perception/lib/config_manager/config_manager.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -312,7 +312,7 @@ bool TLPreprocessor::ProjectLightsAndSelectCamera(
// project light region on each camera's image plane
const
auto
&
camera_names
=
projection_
.
getCameraNamesByDescendingFocalLen
();
for
(
int
cam_id
=
0
;
cam_id
<
static_cast
<
int
>
(
num_cameras_
)
;
++
cam_id
)
{
for
(
size_t
cam_id
=
0
;
cam_id
<
num_cameras_
;
++
cam_id
)
{
const
std
::
string
&
camera_name
=
camera_names
[
cam_id
];
if
(
!
ProjectLights
(
pose
,
camera_name
,
lights
,
&
(
lights_on_image_array_
[
cam_id
]),
...
...
@@ -325,7 +325,7 @@ bool TLPreprocessor::ProjectLightsAndSelectCamera(
}
projections_outside_all_images_
=
(
lights
->
size
()
>
0
);
for
(
int
cam_id
=
0
;
cam_id
<
static_cast
<
int
>
(
num_cameras_
)
;
++
cam_id
)
{
for
(
size_t
cam_id
=
0
;
cam_id
<
num_cameras_
;
++
cam_id
)
{
projections_outside_all_images_
=
projections_outside_all_images_
&&
(
lights_on_image_array_
[
cam_id
].
size
()
<
lights
->
size
());
}
...
...
modules/perception/camera/lib/traffic_light/tracker/BUILD
浏览文件 @
8047dffb
...
...
@@ -26,9 +26,9 @@ cc_library(
],
deps
=
[
":trafficlight_tracker_semantic_proto"
,
"//modules/common/util:file_util"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
],
)
...
...
modules/perception/camera/lib/traffic_light/tracker/semantic_decision.cc
浏览文件 @
8047dffb
...
...
@@ -20,8 +20,8 @@
#include <sstream>
#include <map>
#include "modules/common/util/file.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -42,7 +42,7 @@ bool compare(const SemanticTable& s1, const SemanticTable& s2) {
bool
SemanticReviser
::
Init
(
const
TrafficLightTrackerInitOptions
&
options
)
{
std
::
string
proto_path
=
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
if
(
!
lib
::
ParseProtobuf
FromFile
(
proto_path
,
&
semantic_param_
))
{
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
(
proto_path
,
&
semantic_param_
))
{
AINFO
<<
"load proto param failed, root dir: "
<<
options
.
root_dir
;
return
false
;
}
...
...
@@ -98,7 +98,7 @@ SemanticReviser::ReviseBySemantic(SemanticTable semantic_table,
int
max_color_num
=
0
;
base
::
TLColor
max_color
=
base
::
TLColor
::
TL_UNKNOWN_COLOR
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
semantic_table
.
light_ids
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
semantic_table
.
light_ids
.
size
(
);
++
i
)
{
int
index
=
semantic_table
.
light_ids
.
at
(
i
);
base
::
TrafficLightPtr
light
=
lights_ref
[
index
];
auto
color
=
light
->
status
.
color
;
...
...
@@ -257,7 +257,7 @@ bool SemanticReviser::Track(const TrafficLightTrackerOptions& options,
return
true
;
}
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
lights_ref
.
size
()
);
i
++
)
{
for
(
size_t
i
=
0
;
i
<
lights_ref
.
size
(
);
i
++
)
{
base
::
TrafficLightPtr
light
=
lights_ref
.
at
(
i
);
int
cur_semantic
=
light
->
semantic
;
AINFO
<<
"light "
<<
light
->
id
<<
" semantic "
<<
cur_semantic
;
...
...
@@ -287,7 +287,7 @@ bool SemanticReviser::Track(const TrafficLightTrackerOptions& options,
}
}
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
semantic_table
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
semantic_table
.
size
(
);
++
i
)
{
SemanticTable
cur_semantic_table
=
semantic_table
.
at
(
i
);
ReviseByTimeSeries
(
time_stamp
,
cur_semantic_table
,
&
lights_ref
);
}
...
...
modules/perception/camera/test/BUILD
浏览文件 @
8047dffb
...
...
@@ -536,7 +536,7 @@
# # "//modules/perception/camera/lib/obstacle/tracker/omt:omt_proto",
# # "//modules/perception/camera/lib/obstacle/tracker/omt:target",
# # "//modules/perception/lib/io:file_util",
# # "//modules/
perception/lib/io:protobuf
_util",
# # "//modules/
common/util:file
_util",
# # "@gtest//:main",
# # ]
# # )
...
...
@@ -554,7 +554,7 @@
# "//modules/perception/camera/lib/obstacle/tracker/omt:target",
# "//modules/perception/inference/utils:inference_gemm_lib",
# "//modules/perception/lib/io:file_util",
# "//modules/
perception/lib/io:protobuf
_util",
# "//modules/
common/util:file
_util",
# "@gtest//:main",
# ]
# )
...
...
modules/perception/camera/test/camera_common_util_test.cc
浏览文件 @
8047dffb
...
...
@@ -334,12 +334,12 @@ TEST(UtilTest, GetCybertronWorkRootTest) {
GetCybertronWorkRoot
(
&
work_root
);
EXPECT_EQ
(
work_root
,
""
);
char
cybertron_path
[
80
]
=
"CYBERTRON_PATH=/home/caros/cybertron"
;
char
cybertron_path
[]
=
"CYBERTRON_PATH=/home/caros/cybertron"
;
putenv
(
cybertron_path
);
GetCybertronWorkRoot
(
&
work_root
);
EXPECT_EQ
(
work_root
,
"/home/caros/cybertron"
);
char
module_path
[
80
]
=
"MODULE_PATH=/home/test/perception-camera"
;
char
module_path
[]
=
"MODULE_PATH=/home/test/perception-camera"
;
putenv
(
module_path
);
GetCybertronWorkRoot
(
&
work_root
);
EXPECT_EQ
(
work_root
,
"/home/test/perception-camera"
);
...
...
modules/perception/camera/test/camera_lib_obstacle_detector_yolo_yolo_obstacle_detector_test.cc
浏览文件 @
8047dffb
...
...
@@ -142,7 +142,7 @@ TEST(YoloCameraDetectorTest, inference_init_test) {
lib
::
FileUtil
::
GetAbsolutePath
(
init_options
.
root_dir
,
init_options
.
conf_file
);
yolo
::
YoloParam
yolo_param
;
lib
::
ParseProtobuf
FromFile
(
config_path
,
&
yolo_param
);
apollo
::
common
::
util
::
GetProto
FromFile
(
config_path
,
&
yolo_param
);
yolo
::
YoloParam
origin_yolo_param
;
origin_yolo_param
.
CopyFrom
(
yolo_param
);
yolo_param
.
mutable_model_param
()
->
set_model_type
(
"Unknownnet"
);
...
...
@@ -185,7 +185,7 @@ TEST(YoloCameraDetectorTest, anchor_init_test) {
init_options
.
conf_file
);
yolo
::
YoloParam
yolo_param
;
yolo
::
YoloParam
origin_yolo_param
;
lib
::
ParseProtobuf
FromFile
(
config_path
,
&
yolo_param
);
apollo
::
common
::
util
::
GetProto
FromFile
(
config_path
,
&
yolo_param
);
origin_yolo_param
.
CopyFrom
(
yolo_param
);
yolo_param
.
mutable_model_param
()
->
set_anchors_file
(
"unknown_anchor.txt"
);
{
...
...
@@ -226,7 +226,7 @@ TEST(YoloCameraDetectorTest, type_init_test) {
init_options
.
conf_file
);
yolo
::
YoloParam
yolo_param
;
yolo
::
YoloParam
origin_yolo_param
;
lib
::
ParseProtobuf
FromFile
(
config_path
,
&
yolo_param
);
apollo
::
common
::
util
::
GetProto
FromFile
(
config_path
,
&
yolo_param
);
origin_yolo_param
.
CopyFrom
(
yolo_param
);
yolo_param
.
mutable_model_param
()
->
set_types_file
(
"config.pt"
);
{
...
...
@@ -267,7 +267,7 @@ TEST(YoloCameraDetectorTest, feature_init_test) {
init_options
.
conf_file
);
yolo
::
YoloParam
yolo_param
;
yolo
::
YoloParam
origin_yolo_param
;
lib
::
ParseProtobuf
FromFile
(
config_path
,
&
yolo_param
);
apollo
::
common
::
util
::
GetProto
FromFile
(
config_path
,
&
yolo_param
);
origin_yolo_param
.
CopyFrom
(
yolo_param
);
yolo_param
.
mutable_model_param
()
->
set_feature_file
(
"unknown.pt"
);
{
...
...
modules/perception/camera/test/camera_lib_obstacle_tracker_common_test.cc
浏览文件 @
8047dffb
...
...
@@ -285,7 +285,7 @@ TEST(KalmanConstTest, const_filter_test) {
0.19266443
,
2.05814734
,
0.44203236
,
-
0.36923239
,
-
2.74245158
,
1.71922351
,
0.50960368
,
-
1.24154697
,
-
1.7048239
,
0.80218156
};
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
measurements
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
measurements
.
size
(
);
++
i
)
{
param
<<
measurements
[
i
];
filter
.
Predict
(
1.0
);
filter
.
Correct
(
param
);
...
...
modules/perception/camera/test/camera_lib_obstacle_tracker_omt_reference_test.cc
浏览文件 @
8047dffb
...
...
@@ -15,15 +15,15 @@
*****************************************************************************/
#include "modules/perception/camera/lib/obstacle/tracker/omt/obstacle_reference.h"
#include "gtest/gtest.h"
#include "modules/common/util/file.h"
#include "modules/perception/base/object_types.h"
#include "modules/perception/camera/common/object_template_manager.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/camera/lib/obstacle/tracker/omt/frame_list.h"
#include "modules/perception/camera/lib/obstacle/tracker/omt/omt.pb.h"
#include "modules/perception/camera/lib/obstacle/tracker/omt/target.h"
#include "gtest/gtest.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -46,7 +46,7 @@ TEST(RefTest, update_test) {
"/apollo/modules/perception/testdata/"
"camera/lib/obstacle/tracker/omt/data/models/omt_obstacle_tracker"
,
"config.pt"
);
CHECK
(
lib
::
ParseProtobuf
FromFile
<
omt
::
OmtParam
>
(
CHECK
(
apollo
::
common
::
util
::
GetProto
FromFile
<
omt
::
OmtParam
>
(
omt_config
,
&
omt_param
));
ref
.
Init
(
omt_param
.
reference
(),
1920.0
f
,
1080.0
f
);
std
::
string
sensor_name
=
"onsemi_obstacle"
;
...
...
modules/perception/camera/test/camera_lib_obstacle_tracker_omt_target_test.cc
浏览文件 @
8047dffb
...
...
@@ -13,15 +13,15 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "gtest/gtest.h"
#include "modules/common/util/file.h"
#include "modules/perception/base/object_types.h"
#include "modules/perception/camera/common/object_template_manager.h"
#include "modules/perception/camera/common/util.h"
#include "modules/perception/camera/lib/obstacle/tracker/omt/frame_list.h"
#include "modules/perception/camera/lib/obstacle/tracker/omt/omt.pb.h"
#include "modules/perception/camera/lib/obstacle/tracker/omt/target.h"
#include "gtest/gtest.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
namespace
apollo
{
namespace
perception
{
...
...
@@ -46,7 +46,7 @@ TEST(TargetTest, target_test) {
"omt_obstacle_tracker"
,
"config.pt"
);
ASSERT_TRUE
(
lib
::
ParseProtobuf
FromFile
<
omt
::
OmtParam
>
(
ASSERT_TRUE
(
apollo
::
common
::
util
::
GetProto
FromFile
<
omt
::
OmtParam
>
(
omt_config
,
&
omt_param
));
// first frame with one car object
...
...
@@ -223,7 +223,7 @@ TEST(TargetTest, clapping_velocity_test) {
"omt_obstacle_tracker"
,
"config.pt"
);
ASSERT_TRUE
(
lib
::
ParseProtobuf
FromFile
<
omt
::
OmtParam
>
(
ASSERT_TRUE
(
apollo
::
common
::
util
::
GetProto
FromFile
<
omt
::
OmtParam
>
(
omt_config
,
&
omt_param
));
auto
read_pos_and_theta_vec
=
[](
const
std
::
string
&
fname
)
...
...
@@ -263,7 +263,7 @@ TEST(TargetTest, clapping_velocity_test) {
std
::
string
pos_theta_filename
=
"/apollo/modules/perception/testdata/"
"camera/lib/obstacle/tracker/omt/test_data/target_pos_theta1.txt"
;
auto
pos_and_theta_vec
=
read_pos_and_theta_vec
(
pos_theta_filename
);
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
pos_and_theta_vec
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
pos_and_theta_vec
.
size
(
);
++
i
)
{
double
ts
=
i
*
0.066
;
CameraFrame
frame
;
base
::
ObjectPtr
object
(
new
base
::
Object
);
...
...
@@ -322,7 +322,7 @@ TEST(TargetTest, clapping_velocity_test) {
std
::
string
pos_theta_filename
=
"/apollo/modules/perception/testdata/"
"camera/lib/obstacle/tracker/omt/test_data/target_pos_theta1.txt"
;
auto
pos_and_theta_vec
=
read_pos_and_theta_vec
(
pos_theta_filename
);
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
pos_and_theta_vec
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
pos_and_theta_vec
.
size
(
);
++
i
)
{
CameraFrame
frame
;
base
::
ObjectPtr
object
(
new
base
::
Object
);
base
::
BBox2DF
bbox
(
500
,
500
,
1000
,
1000
);
...
...
@@ -377,7 +377,7 @@ TEST(TargetTest, clapping_velocity_test) {
std
::
string
pos_theta_filename
=
"/apollo/modules/perception/testdata/"
"camera/lib/obstacle/tracker/omt/test_data/target_pos_theta2.txt"
;
auto
pos_and_theta_vec
=
read_pos_and_theta_vec
(
pos_theta_filename
);
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
pos_and_theta_vec
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
pos_and_theta_vec
.
size
(
);
++
i
)
{
double
ts
=
i
*
0.066
;
CameraFrame
frame
;
base
::
ObjectPtr
object
(
new
base
::
Object
);
...
...
@@ -435,7 +435,7 @@ TEST(TargetTest, clapping_velocity_test) {
std
::
string
pos_theta_filename
=
"/apollo/modules/perception/testdata/"
"camera/lib/obstacle/tracker/omt/test_data/target_pos_theta3.txt"
;
auto
pos_and_theta_vec
=
read_pos_and_theta_vec
(
pos_theta_filename
);
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
pos_and_theta_vec
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
pos_and_theta_vec
.
size
(
);
++
i
)
{
double
ts
=
i
*
0.033
;
CameraFrame
frame
;
base
::
ObjectPtr
object
(
new
base
::
Object
);
...
...
@@ -494,7 +494,7 @@ TEST(TargetTest, clapping_velocity_test) {
std
::
string
pos_theta_filename
=
"/apollo/modules/perception/testdata/"
"camera/lib/obstacle/tracker/omt/test_data/target_pos_theta4.txt"
;
auto
pos_and_theta_vec
=
read_pos_and_theta_vec
(
pos_theta_filename
);
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
pos_and_theta_vec
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
pos_and_theta_vec
.
size
(
);
++
i
)
{
double
ts
=
i
*
0.033
;
CameraFrame
frame
;
base
::
ObjectPtr
object
(
new
base
::
Object
);
...
...
modules/perception/camera/test/camera_lib_traffic_light_detector_recognition_test.cc
浏览文件 @
8047dffb
...
...
@@ -73,7 +73,6 @@ TEST(RecognizeTest, yellow) {
#ifndef CPU_ONLY
ASSERT_TRUE
(
recognition
->
Detect
(
recognition_options
,
&
frame
));
// 直接 EXPECT_EQ 会出 core
AINFO
<<
"COLOR "
<<
static_cast
<
int
>
(
lights
[
0
]
->
status
.
color
);
ASSERT_TRUE
(
base
::
TLColor
::
TL_YELLOW
==
lights
[
0
]
->
status
.
color
);
#endif
...
...
@@ -130,7 +129,6 @@ TEST(RecognizeTest, red) {
#ifndef CPU_ONLY
ASSERT_TRUE
(
recognition
->
Detect
(
recognition_options
,
&
frame
));
// 直接 EXPECT_EQ 会出 core
AINFO
<<
"COLOR "
<<
static_cast
<
int
>
(
lights
[
0
]
->
status
.
color
);
ASSERT_TRUE
(
base
::
TLColor
::
TL_RED
==
lights
[
0
]
->
status
.
color
);
#endif
...
...
@@ -184,7 +182,6 @@ TEST(RecognizeTest, green) {
frame
.
traffic_lights
=
lights
;
ASSERT_TRUE
(
recognition
->
Detect
(
recognition_options
,
&
frame
));
// 直接 EXPECT_EQ 会出 core
AINFO
<<
"COLOR "
<<
static_cast
<
int
>
(
lights
[
0
]
->
status
.
color
);
ASSERT_TRUE
(
base
::
TLColor
::
TL_GREEN
==
lights
[
0
]
->
status
.
color
);
}
...
...
@@ -240,7 +237,6 @@ TEST(RecognizeTest, black) {
#ifndef CPU_ONLY
ASSERT_TRUE
(
recognition
->
Detect
(
recognition_options
,
&
frame
));
// 直接 EXPECT_EQ 会出 core
AINFO
<<
"COLOR "
<<
static_cast
<
int
>
(
lights
[
0
]
->
status
.
color
);
ASSERT_TRUE
(
base
::
TLColor
::
TL_BLACK
==
lights
[
0
]
->
status
.
color
);
#endif
...
...
@@ -293,7 +289,6 @@ TEST(RecognizeTest, no_detection) {
#ifndef CPU_ONLY
ASSERT_TRUE
(
recognition
->
Detect
(
recognition_options
,
&
frame
));
// 直接 EXPECT_EQ 会出 core
AINFO
<<
"COLOR "
<<
static_cast
<
int
>
(
lights
[
0
]
->
status
.
color
);
ASSERT_TRUE
(
base
::
TLColor
::
TL_UNKNOWN_COLOR
==
lights
[
0
]
->
status
.
color
);
#endif
...
...
@@ -404,7 +399,6 @@ TEST(RecognizeTest, quadrate) {
#ifndef CPU_ONLY
ASSERT_TRUE
(
recognition
->
Detect
(
recognition_options
,
&
frame
));
// 直接 EXPECT_EQ 会出 core
AINFO
<<
"COLOR "
<<
static_cast
<
int
>
(
lights
[
0
]
->
status
.
color
);
ASSERT_TRUE
(
base
::
TLColor
::
TL_GREEN
==
lights
[
0
]
->
status
.
color
);
#endif
...
...
@@ -467,7 +461,6 @@ TEST(RecognizeTest, horizontal) {
#ifndef CPU_ONLY
ASSERT_TRUE
(
recognition
->
Detect
(
recognition_options
,
&
frame
));
// 直接 EXPECT_EQ 会出 core
AINFO
<<
"COLOR "
<<
static_cast
<
int
>
(
lights
[
0
]
->
status
.
color
);
ASSERT_TRUE
(
base
::
TLColor
::
TL_GREEN
==
lights
[
0
]
->
status
.
color
);
#endif
...
...
modules/perception/camera/test/camera_lib_traffic_light_tracker_test.cc
浏览文件 @
8047dffb
...
...
@@ -35,7 +35,7 @@ void do_test(std::shared_ptr<SemanticReviser> _reviser,
TrafficLightTrackerOptions
option
;
CameraFrame
frame
;
frame
.
timestamp
=
100
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
color_list
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
color_list
.
size
(
);
++
i
)
{
std
::
vector
<
base
::
TrafficLightPtr
>
light
;
light
.
emplace_back
(
new
base
::
TrafficLight
);
light
[
0
]
->
status
.
color
=
base
::
TLColor
(
color_list
[
i
]);
...
...
@@ -96,7 +96,7 @@ TEST(SemanticReviser, mix) {
TrafficLightTrackerOptions
option
;
CameraFrame
frame
;
frame
.
timestamp
=
100
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
color_list
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
color_list
.
size
(
);
++
i
)
{
std
::
vector
<
base
::
TrafficLightPtr
>
light
;
light
.
emplace_back
(
new
base
::
TrafficLight
);
light
[
0
]
->
status
.
color
=
base
::
TLColor
(
color_list
[
i
]);
...
...
@@ -123,7 +123,7 @@ TEST(SemanticReviser, mix_yellow) {
TrafficLightTrackerOptions
option
;
CameraFrame
frame
;
frame
.
timestamp
=
100
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
color_list
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
color_list
.
size
(
);
++
i
)
{
std
::
vector
<
base
::
TrafficLightPtr
>
light
;
light
.
emplace_back
(
new
base
::
TrafficLight
);
light
[
0
]
->
status
.
color
=
base
::
TLColor
(
color_list
[
i
]);
...
...
@@ -150,7 +150,7 @@ TEST(SemanticReviser, mix_black) {
TrafficLightTrackerOptions
option
;
CameraFrame
frame
;
frame
.
timestamp
=
100
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
color_list
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
color_list
.
size
(
);
++
i
)
{
std
::
vector
<
base
::
TrafficLightPtr
>
light
;
light
.
emplace_back
(
new
base
::
TrafficLight
);
light
[
0
]
->
status
.
color
=
base
::
TLColor
(
color_list
[
i
]);
...
...
@@ -177,7 +177,7 @@ TEST(SemanticReviser, unknown_to_black) {
TrafficLightTrackerOptions
option
;
CameraFrame
frame
;
frame
.
timestamp
=
100
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
color_list
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
color_list
.
size
(
);
++
i
)
{
std
::
vector
<
base
::
TrafficLightPtr
>
light
;
light
.
emplace_back
(
new
base
::
TrafficLight
);
light
[
0
]
->
status
.
color
=
base
::
TLColor
(
color_list
[
i
]);
...
...
@@ -204,7 +204,7 @@ TEST(SemanticReviser, black_to_unknown) {
TrafficLightTrackerOptions
option
;
CameraFrame
frame
;
frame
.
timestamp
=
100
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
color_list
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
color_list
.
size
(
);
++
i
)
{
std
::
vector
<
base
::
TrafficLightPtr
>
light
;
light
.
emplace_back
(
new
base
::
TrafficLight
);
light
[
0
]
->
status
.
color
=
base
::
TLColor
(
color_list
[
i
]);
...
...
@@ -263,7 +263,7 @@ TEST(SemanticReviser, mix_yellow_red_flash) {
TrafficLightTrackerOptions
option
;
CameraFrame
frame
;
frame
.
timestamp
=
100
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
color_list
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
color_list
.
size
(
);
++
i
)
{
std
::
vector
<
base
::
TrafficLightPtr
>
light
;
light
.
emplace_back
(
new
base
::
TrafficLight
);
light
[
0
]
->
status
.
color
=
base
::
TLColor
(
color_list
[
i
]);
...
...
@@ -327,7 +327,7 @@ TEST(SemanticReviser, green_blink) {
options
.
conf_file
=
"semantic.pt"
;
reviser
->
Init
(
options
);
frame
.
timestamp
=
100
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
color_list
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
color_list
.
size
(
);
++
i
)
{
std
::
vector
<
base
::
TrafficLightPtr
>
light
;
light
.
emplace_back
(
new
base
::
TrafficLight
);
light
[
0
]
->
status
.
color
=
base
::
TLColor
(
color_list
[
i
]);
...
...
modules/perception/camera/tools/lane_detection/BUILD
浏览文件 @
8047dffb
...
...
@@ -31,15 +31,15 @@ cc_binary(
":lane_common"
,
"//external:gflags"
,
"//cybertron"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/common/util:file_util"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/camera/lib/calibration_service/online_calibration_service:online_calibration_service"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/camera/lib/lane/detector/denseline:denseline_lane_detector"
,
"//modules/perception/camera/lib/lane/postprocessor/denseline:denseline_lane_postprocessor"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/common/io:io_util"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
]
)
...
...
modules/perception/camera/tools/lane_detection/lane_common.cc
浏览文件 @
8047dffb
...
...
@@ -46,8 +46,8 @@ void show_detect_point_set(const cv::Mat& image,
int
draw_size
=
2
;
cv
::
Mat
draw_mat
=
image
.
clone
();
for
(
in
t
line_idx
=
0
;
line_idx
<
static_cast
<
int
>
(
detect_laneline_point_set
.
size
());
line_idx
++
)
{
for
(
size_
t
line_idx
=
0
;
line_idx
<
detect_laneline_point_set
.
size
();
++
line_idx
)
{
if
(
line_idx
==
0
)
{
color
=
cv
::
Scalar
(
0
,
255
,
0
);
}
else
if
(
line_idx
==
1
)
{
...
...
@@ -57,8 +57,8 @@ void show_detect_point_set(const cv::Mat& image,
}
else
if
(
line_idx
==
3
)
{
color
=
cv
::
Scalar
(
0
,
255
,
255
);
}
for
(
in
t
i
=
0
;
i
<
static_cast
<
int
>
(
detect_laneline_point_set
[
line_idx
].
size
());
i
++
)
{
for
(
size_
t
i
=
0
;
i
<
detect_laneline_point_set
[
line_idx
].
size
();
++
i
)
{
int
point_x
=
detect_laneline_point_set
[
line_idx
][
i
].
x
;
int
point_y
=
...
...
@@ -77,8 +77,7 @@ void show_all_infer_point_set(const cv::Mat& image,
int
draw_size
=
2
;
cv
::
Mat
draw_mat
=
image
.
clone
();
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
infer_point_set
.
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
infer_point_set
.
size
();
++
i
)
{
int
point_x
=
infer_point_set
[
i
].
x
;
int
point_y
=
infer_point_set
[
i
].
y
;
cv
::
circle
(
draw_mat
,
...
...
@@ -101,7 +100,7 @@ void show_lane_lines(const cv::Mat& image,
cv
::
Scalar
color
=
cv
::
Scalar
(
0
,
255
,
0
);
int
draw_size
=
2
;
cv
::
Mat
draw_mat
=
image
.
clone
();
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
lane_marks
.
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
lane_marks
.
size
();
++
i
)
{
base
::
LaneLinePositionType
pos_type
=
lane_marks
[
i
].
pos_type
;
if
(
pos_type
==
base
::
LaneLinePositionType
::
EGO_LEFT
||
pos_type
==
base
::
LaneLinePositionType
::
EGO_RIGHT
)
{
...
...
@@ -119,7 +118,7 @@ void show_lane_lines(const cv::Mat& image,
float
fd
=
lane_marks
[
i
].
curve_image_coord
.
d
;
float
y0
=
lane_marks
[
i
].
curve_image_coord
.
x_start
;
float
y1
=
lane_marks
[
i
].
curve_image_coord
.
x_end
;
for
(
int
j
=
static_cast
<
int
>
(
y0
);
j
<=
static_cast
<
int
>
(
y1
);
j
++
)
{
for
(
int
j
=
static_cast
<
int
>
(
y0
);
j
<=
static_cast
<
int
>
(
y1
);
++
j
)
{
int
x
=
fa
*
pow
(
j
,
3
)
+
fb
*
pow
(
j
,
2
)
+
fc
*
j
+
fd
;
cv
::
circle
(
draw_mat
,
cv
::
Point
(
x
,
j
),
draw_size
,
color
);
}
...
...
@@ -169,7 +168,7 @@ void show_lane_ccs(const std::vector<unsigned char>& lane_map,
const
std
::
string
&
save_path
)
{
cv
::
Mat
lane_map_draw
=
cv
::
Mat
::
zeros
(
lane_map_height
,
lane_map_width
,
CV_8UC1
);
for
(
int
y
=
0
;
y
<
lane_map_height
;
y
++
)
{
for
(
int
y
=
0
;
y
<
lane_map_height
;
++
y
)
{
for
(
int
x
=
0
;
x
<
lane_map_width
;
x
++
)
{
lane_map_draw
.
at
<
unsigned
char
>
(
y
,
x
)
=
255
-
lane_map
[
y
*
lane_map_width
+
x
]
*
255
;
...
...
@@ -179,11 +178,11 @@ void show_lane_ccs(const std::vector<unsigned char>& lane_map,
cv
::
cvtColor
(
lane_map_draw
,
lane_draw
,
8
);
cv
::
Scalar
color
;
std
::
string
msg
=
""
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
lane_ccs
.
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
lane_ccs
.
size
();
++
i
)
{
std
::
vector
<
base
::
Point2DI
>
pixels
=
lane_ccs
[
i
].
GetPixels
();
base
::
BBox2DI
bbox1
=
lane_ccs
[
i
].
GetBBox
();
int
find_index
=
-
1
;
for
(
int
j
=
0
;
j
<
static_cast
<
int
>
(
select_lane_ccs
.
size
());
j
++
)
{
for
(
size_t
j
=
0
;
j
<
select_lane_ccs
.
size
();
++
j
)
{
base
::
BBox2DI
bbox2
=
select_lane_ccs
[
j
].
GetBBox
();
if
(
bbox1
.
xmin
==
bbox2
.
xmin
&&
bbox1
.
xmax
==
bbox2
.
xmax
&&
...
...
@@ -202,7 +201,7 @@ void show_lane_ccs(const std::vector<unsigned char>& lane_map,
}
else
{
color
=
cv
::
Scalar
(
0
,
0
,
0
);
}
for
(
int
j
=
0
;
j
<
static_cast
<
int
>
(
pixels
.
size
());
j
++
)
{
for
(
size_t
j
=
0
;
j
<
pixels
.
size
();
++
j
)
{
int
x
=
pixels
[
j
].
x
;
int
y
=
pixels
[
j
].
y
;
cv
::
circle
(
lane_draw
,
cv
::
Point
(
x
,
y
),
1
,
color
);
...
...
@@ -221,7 +220,7 @@ void output_laneline_to_json(const std::vector<base::LaneLine> &lane_objects,
AINFO
<<
"lane line num: "
<<
lane_line_size
;
std
::
string
msg
=
"lane line info: "
;
fprintf
(
file_save
,
"[
\n
"
);
for
(
int
j
=
0
;
j
<
lane_line_size
;
j
++
)
{
for
(
int
j
=
0
;
j
<
lane_line_size
;
++
j
)
{
const
base
::
LaneLineCubicCurve
&
curve_camera
=
lane_objects
[
j
].
curve_camera_coord
;
const
base
::
LaneLineCubicCurve
&
curve_img
...
...
@@ -244,8 +243,8 @@ void output_laneline_to_json(const std::vector<base::LaneLine> &lane_objects,
// camera_image_point_set
fprintf
(
file_save
,
"
\"
camera_point_set
\"
:
\n
"
);
fprintf
(
file_save
,
"["
);
for
(
int
k
=
0
;
k
<
static_cast
<
int
>
(
camera_point_set
.
size
());
k
++
)
{
if
(
k
<
static_cast
<
int
>
(
camera_point_set
.
size
()
)
-
1
)
{
for
(
size_t
k
=
0
;
k
<
camera_point_set
.
size
();
++
k
)
{
if
(
k
<
camera_point_set
.
size
(
)
-
1
)
{
fprintf
(
file_save
,
"{
\"
x
\"
:%.4f,
\"
y
\"
:%.4f,
\"
z
\"
:%.4f},"
,
camera_point_set
[
k
].
x
,
camera_point_set
[
k
].
y
,
camera_point_set
[
k
].
z
);
...
...
@@ -268,8 +267,8 @@ void output_laneline_to_json(const std::vector<base::LaneLine> &lane_objects,
// curve_image_point_set
fprintf
(
file_save
,
"
\"
image_point_set
\"
:
\n
"
);
fprintf
(
file_save
,
"["
);
for
(
int
k
=
0
;
k
<
static_cast
<
int
>
(
image_point_set
.
size
());
k
++
)
{
if
(
k
<
static_cast
<
int
>
(
image_point_set
.
size
()
)
-
1
)
{
for
(
size_t
k
=
0
;
k
<
image_point_set
.
size
();
++
k
)
{
if
(
k
<
image_point_set
.
size
(
)
-
1
)
{
fprintf
(
file_save
,
"{
\"
x
\"
:%.4f,
\"
y
\"
:%.4f},"
,
image_point_set
[
k
].
x
,
image_point_set
[
k
].
y
);
}
else
{
...
...
@@ -296,7 +295,7 @@ void output_laneline_to_txt(const std::vector<base::LaneLine> &lane_objects,
int
lane_line_size
=
lane_objects
.
size
();
AINFO
<<
"lane line num: "
<<
lane_line_size
;
fprintf
(
file_save
,
"lane_line_num=%d
\n
"
,
lane_line_size
);
for
(
int
j
=
0
;
j
<
lane_line_size
;
j
++
)
{
for
(
int
j
=
0
;
j
<
lane_line_size
;
++
j
)
{
base
::
LaneLineCubicCurve
curve_camera
=
lane_objects
[
j
].
curve_camera_coord
;
base
::
LaneLineCubicCurve
curve_img
=
lane_objects
[
j
].
curve_image_coord
;
fprintf
(
file_save
,
"type=%d
\n
"
,
lane_objects
[
j
].
type
);
...
...
@@ -317,13 +316,13 @@ void output_laneline_to_txt(const std::vector<base::LaneLine> &lane_objects,
std
::
vector
<
base
::
Point3DF
>
curve_camera_point_set
=
lane_objects
[
j
].
curve_camera_point_set
;
fprintf
(
file_save
,
"curve_image_point_set:
\n
"
);
for
(
int
k
=
0
;
k
<
static_cast
<
int
>
(
curve_image_point_set
.
size
());
k
++
)
{
for
(
size_t
k
=
0
;
k
<
curve_image_point_set
.
size
();
++
k
)
{
fprintf
(
file_save
,
"[%f %f] "
,
curve_image_point_set
[
k
].
x
,
curve_image_point_set
[
k
].
y
);
}
fprintf
(
file_save
,
"
\n
"
);
fprintf
(
file_save
,
"curve_camera_point_set:
\n
"
);
for
(
int
k
=
0
;
k
<
static_cast
<
int
>
(
curve_camera_point_set
.
size
());
k
++
)
{
for
(
size_t
k
=
0
;
k
<
curve_camera_point_set
.
size
();
++
k
)
{
fprintf
(
file_save
,
"[%f %f %f] "
,
curve_camera_point_set
[
k
].
x
,
curve_camera_point_set
[
k
].
y
,
curve_camera_point_set
[
k
].
z
);
}
...
...
@@ -340,8 +339,7 @@ void show_detect_point_set(const cv::Mat& image,
int
draw_size
=
2
;
cv
::
Mat
draw_mat
=
image
.
clone
();
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
img_laneline_point_set
.
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
img_laneline_point_set
.
size
();
++
i
)
{
const
base
::
Point2DF
&
point
=
img_laneline_point_set
[
i
];
cv
::
circle
(
draw_mat
,
cv
::
Point
(
point
.
x
,
point
.
y
),
...
...
@@ -359,8 +357,7 @@ void show_neighbor_point_set(const cv::Mat& image,
int
draw_size
=
2
;
cv
::
Mat
draw_mat
=
image
.
clone
();
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
img_laneline_point_set
.
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
img_laneline_point_set
.
size
();
++
i
)
{
const
base
::
Point2DF
&
point
=
img_laneline_point_set
[
i
];
cv
::
circle
(
draw_mat
,
cv
::
Point
(
point
.
x
,
point
.
y
),
...
...
@@ -392,8 +389,7 @@ void show_detect_point_set(const cv::Mat& image,
int
draw_size
=
2
;
cv
::
Mat
draw_mat
=
image
.
clone
();
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
img_laneline_point_set
.
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
img_laneline_point_set
.
size
();
++
i
)
{
const
base
::
Point2DF
&
point
=
img_laneline_point_set
[
i
];
std
::
string
label
=
cv
::
format
(
"%.2f"
,
point_score_vec
[
i
]);
cv
::
putText
(
draw_mat
,
label
,
cv
::
Point
(
point
.
x
,
point
.
y
),
...
...
modules/perception/camera/tools/obstacle_detection/BUILD
浏览文件 @
8047dffb
...
...
@@ -14,8 +14,8 @@ cc_binary(
],
deps
=
[
"@gtest"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/base:base"
,
"//modules/perception/camera/lib/interface:interface"
,
"//modules/perception/common/io:io_util"
,
]
)
...
...
modules/perception/camera/tools/offline/BUILD
浏览文件 @
8047dffb
...
...
@@ -56,8 +56,8 @@ cc_binary(
"//modules/perception/base:base"
,
"//modules/perception/camera/app:obstacle_camera_perception"
,
"//modules/perception/camera/common:common"
,
"//modules/perception/lib/utils:utils"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/utils:utils"
,
]
)
...
...
modules/perception/camera/tools/offline/offline_obstacle_pipeline.cc
浏览文件 @
8047dffb
...
...
@@ -99,7 +99,7 @@ int work() {
std
::
vector
<
DataProvider
>
data_providers
(
camera_names
.
size
());
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
camera_names
.
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
camera_names
.
size
();
++
i
)
{
data_options
.
sensor_name
=
camera_names
[
i
];
CHECK
(
data_providers
[
i
].
Init
(
data_options
));
name_provider_map
.
insert
(
std
::
pair
<
std
::
string
,
DataProvider
*>
(
...
...
@@ -134,7 +134,7 @@ int work() {
// pitch_angle and project_matrix
std
::
map
<
std
::
string
,
float
>
name_camera_ground_height_map
;
std
::
map
<
std
::
string
,
float
>
name_camera_pitch_angle_diff_map
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
camera_names
.
size
());
i
++
)
{
for
(
size_t
i
=
0
;
i
<
camera_names
.
size
();
++
i
)
{
Eigen
::
Affine3d
c2g
;
if
(
!
transform_server
.
QueryTransform
(
camera_names
[
i
],
"ground"
,
&
c2g
))
{
AINFO
<<
"Failed to query transform from "
<<
camera_names
[
i
]
...
...
modules/perception/camera/tools/offline/visualizer.cc
浏览文件 @
8047dffb
...
...
@@ -49,7 +49,7 @@ bool Visualizer::Init(const std::vector<std::string> &camera_names,
wide_pixel_
=
800
;
m2pixel_
=
6
;
for
(
int
i
=
0
;
i
<
static_cast
<
int
>
(
camera_names
.
size
()
);
++
i
)
{
for
(
size_t
i
=
0
;
i
<
camera_names
.
size
(
);
++
i
)
{
camera_image_
[
camera_names
[
i
]]
=
cv
::
Mat
(
small_h_
,
small_w_
,
CV_8UC3
,
cv
::
Scalar
(
0
,
0
,
0
));
}
...
...
modules/perception/lib/io/BUILD
浏览文件 @
8047dffb
...
...
@@ -35,15 +35,4 @@ cc_test(
],
)
cc_library
(
name
=
"protobuf_util"
,
hdrs
=
[
"protobuf_util.h"
,
],
deps
=
[
"//cybertron"
,
],
)
cpplint
()
modules/perception/lib/io/protobuf_util.h
已删除
100644 → 0
浏览文件 @
4c76cc6c
/******************************************************************************
* 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 <string>
#include "google/protobuf/io/zero_copy_stream_impl.h"
#include "google/protobuf/text_format.h"
#include "cybertron/common/log.h"
namespace
apollo
{
namespace
perception
{
namespace
lib
{
// @brief load protobuf(TXT) data from file.
template
<
typename
T
>
bool
ParseProtobufFromFile
(
const
std
::
string
&
file_name
,
T
*
pb
)
{
int
fd
=
open
(
file_name
.
c_str
(),
O_RDONLY
);
if
(
fd
<
0
)
{
AERROR
<<
"ProtobufParser load file failed. file: "
<<
file_name
;
return
false
;
}
google
::
protobuf
::
io
::
FileInputStream
fs
(
fd
);
if
(
!
google
::
protobuf
::
TextFormat
::
Parse
(
&
fs
,
pb
))
{
AERROR
<<
"ProtobufParser parse data failed. file:"
<<
file_name
;
close
(
fd
);
return
false
;
}
close
(
fd
);
return
true
;
}
}
// namespace lib
}
// namespace perception
}
// namespace apollo
modules/perception/onboard/component/BUILD
浏览文件 @
8047dffb
...
...
@@ -38,6 +38,7 @@ cc_library(
"//modules/common/proto:error_code_proto"
,
"//modules/common/proto:geometry_proto"
,
"//modules/common/proto:header_proto"
,
"//modules/common/util:file_util"
,
"//modules/localization/proto:localization_proto"
,
"//modules/common/math:math"
,
"//modules/common/time:time"
,
...
...
@@ -48,7 +49,6 @@ cc_library(
"//modules/perception/lib/registerer"
,
"//modules/perception/lib/singleton:singleton"
,
"//modules/perception/lib/io:file_util"
,
"//modules/perception/lib/io:protobuf_util"
,
"//modules/perception/common:perception_gflags"
,
"//modules/drivers/proto:sensor_proto"
,
"//modules/map/proto:map_proto"
,
...
...
modules/perception/onboard/component/fusion_camera_detection_component.cc
浏览文件 @
8047dffb
...
...
@@ -27,9 +27,9 @@
#include <iomanip>
#include "modules/common/math/math_utils.h"
#include "modules/common/util/file.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/lib/utils/time_util.h"
#include "cybertron/common/log.h"
#include "modules/perception/common/sensor_manager/sensor_manager.h"
...
...
@@ -51,7 +51,7 @@ static int GetGpuId(
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
config_file
=
lib
::
FileUtil
::
GetAbsolutePath
(
work_root
,
config_file
);
if
(
!
lib
::
ParseProtobuf
FromFile
<
camera
::
app
::
PerceptionParam
>
(
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
<
camera
::
app
::
PerceptionParam
>
(
config_file
,
&
perception_param
))
{
AERROR
<<
"Read config failed: "
<<
config_file
;
...
...
modules/perception/onboard/component/trafficlights_perception_component.cc
浏览文件 @
8047dffb
...
...
@@ -31,10 +31,10 @@
#include "cybertron/time/time.h"
#include "modules/common/math/math_utils.h"
#include "modules/common/time/time_util.h"
#include "modules/common/util/file.h"
#include "modules/perception/camera/common/data_provider.h"
#include "modules/perception/common/sensor_manager/sensor_manager.h"
#include "modules/perception/lib/io/file_util.h"
#include "modules/perception/lib/io/protobuf_util.h"
#include "modules/perception/lib/singleton/singleton.h"
#include "modules/perception/lib/utils/perf.h"
#include "modules/perception/lib/utils/time_util.h"
...
...
@@ -55,7 +55,7 @@ static int GetGpuId(
lib
::
FileUtil
::
GetAbsolutePath
(
options
.
root_dir
,
options
.
conf_file
);
config_file
=
lib
::
FileUtil
::
GetAbsolutePath
(
work_root
,
config_file
);
if
(
!
lib
::
ParseProtobuf
FromFile
<
camera
::
app
::
TrafficLightParam
>
(
if
(
!
apollo
::
common
::
util
::
GetProto
FromFile
<
camera
::
app
::
TrafficLightParam
>
(
config_file
,
&
trafficlight_param
))
{
AERROR
<<
"Read config failed: "
<<
config_file
;
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录