Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
16cff894
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,发现更多精彩内容 >>
提交
16cff894
编写于
8月 02, 2017
作者:
A
Aaron Xiao
提交者:
Jiangtao Hu
8月 02, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Simple code clean of prediction module.
上级
516fb93d
变更
17
显示空白变更内容
内联
并排
Showing
17 changed file
with
62 addition
and
82 deletion
+62
-82
modules/prediction/evaluator/evaluator_factory.cc
modules/prediction/evaluator/evaluator_factory.cc
+1
-1
modules/prediction/evaluator/evaluator_factory.h
modules/prediction/evaluator/evaluator_factory.h
+2
-2
modules/prediction/evaluator/evaluator_manager.cc
modules/prediction/evaluator/evaluator_manager.cc
+3
-6
modules/prediction/evaluator/evaluator_manager.h
modules/prediction/evaluator/evaluator_manager.h
+1
-2
modules/prediction/evaluator/evaluator_manager_test.cc
modules/prediction/evaluator/evaluator_manager_test.cc
+5
-7
modules/prediction/evaluator/vehicle/mlp_evaluator.cc
modules/prediction/evaluator/vehicle/mlp_evaluator.cc
+9
-7
modules/prediction/evaluator/vehicle/mlp_evaluator.h
modules/prediction/evaluator/vehicle/mlp_evaluator.h
+5
-5
modules/prediction/evaluator/vehicle/mlp_evaluator_test.cc
modules/prediction/evaluator/vehicle/mlp_evaluator_test.cc
+4
-4
modules/prediction/prediction.cc
modules/prediction/prediction.cc
+2
-5
modules/prediction/predictor/pedestrian/regional_predictor.cc
...les/prediction/predictor/pedestrian/regional_predictor.cc
+5
-4
modules/prediction/predictor/predictor.cc
modules/prediction/predictor/predictor.cc
+4
-9
modules/prediction/predictor/predictor_factory.cc
modules/prediction/predictor/predictor_factory.cc
+2
-3
modules/prediction/predictor/predictor_manager.cc
modules/prediction/predictor/predictor_manager.cc
+5
-9
modules/prediction/predictor/predictor_manager.h
modules/prediction/predictor/predictor_manager.h
+1
-3
modules/prediction/predictor/predictor_manager_test.cc
modules/prediction/predictor/predictor_manager_test.cc
+5
-7
modules/prediction/predictor/vehicle/free_move_predictor.cc
modules/prediction/predictor/vehicle/free_move_predictor.cc
+7
-7
modules/prediction/predictor/vehicle/free_move_predictor_test.cc
.../prediction/predictor/vehicle/free_move_predictor_test.cc
+1
-1
未找到文件。
modules/prediction/evaluator/evaluator_factory.cc
浏览文件 @
16cff894
...
...
@@ -16,8 +16,8 @@
#include "modules/prediction/evaluator/evaluator_factory.h"
#include "modules/prediction/evaluator/vehicle/mlp_evaluator.h"
#include "modules/common/log.h"
#include "modules/prediction/evaluator/vehicle/mlp_evaluator.h"
namespace
apollo
{
namespace
prediction
{
...
...
modules/prediction/evaluator/evaluator_factory.h
浏览文件 @
16cff894
...
...
@@ -24,10 +24,10 @@
#include <memory>
#include "modules/common/macro.h"
#include "modules/common/util/factory.h"
#include "modules/prediction/evaluator/evaluator.h"
#include "modules/prediction/proto/prediction_conf.pb.h"
#include "modules/common/util/factory.h"
#include "modules/common/macro.h"
/**
* @namespace apollo::prediction
...
...
modules/prediction/evaluator/evaluator_manager.cc
浏览文件 @
16cff894
...
...
@@ -16,10 +16,10 @@
#include "modules/prediction/evaluator/evaluator_manager.h"
#include "modules/common/log.h"
#include "modules/prediction/evaluator/vehicle/mlp_evaluator.h"
#include "modules/prediction/container/container_manager.h"
#include "modules/prediction/container/obstacles/obstacles_container.h"
#include "modules/common/log.h"
namespace
apollo
{
namespace
prediction
{
...
...
@@ -64,11 +64,8 @@ void EvaluatorManager::Init(const PredictionConf& config) {
Evaluator
*
EvaluatorManager
::
GetEvaluator
(
const
ObstacleConf
::
EvaluatorType
&
type
)
{
if
(
evaluators_
.
find
(
type
)
!=
evaluators_
.
end
())
{
return
evaluators_
[
type
].
get
();
}
else
{
return
nullptr
;
}
auto
it
=
evaluators_
.
find
(
type
);
return
it
!=
evaluators_
.
end
()
?
it
->
second
.
get
()
:
nullptr
;
}
void
EvaluatorManager
::
Run
(
...
...
modules/prediction/evaluator/evaluator_manager.h
浏览文件 @
16cff894
...
...
@@ -84,8 +84,7 @@ class EvaluatorManager {
void
RegisterEvaluators
();
private:
std
::
map
<
ObstacleConf
::
EvaluatorType
,
std
::
unique_ptr
<
Evaluator
>>
evaluators_
;
std
::
map
<
ObstacleConf
::
EvaluatorType
,
std
::
unique_ptr
<
Evaluator
>>
evaluators_
;
ObstacleConf
::
EvaluatorType
vehicle_on_lane_evaluator_
=
ObstacleConf
::
MLP_EVALUATOR
;
...
...
modules/prediction/evaluator/evaluator_manager_test.cc
浏览文件 @
16cff894
...
...
@@ -14,13 +14,13 @@
* limitations under the License.
*****************************************************************************/
#include
<string>
#include
"modules/prediction/evaluator/evaluator_manager.h"
#include <string>
#include "gtest/gtest.h"
#include "modules/prediction/evaluator/evaluator_manager.h"
#include "modules/prediction/proto/prediction_conf.pb.h"
#include "modules/common/util/file.h"
#include "modules/prediction/proto/prediction_conf.pb.h"
namespace
apollo
{
namespace
prediction
{
...
...
@@ -38,10 +38,8 @@ class EvaluatorManagerTest : public ::testing::Test {
TEST_F
(
EvaluatorManagerTest
,
GetEvaluators
)
{
std
::
string
conf_file
=
"modules/prediction/testdata/prediction_conf.pb.txt"
;
bool
ret_load_conf
=
::
apollo
::
common
::
util
::
GetProtoFromFile
(
conf_file
,
&
conf_
);
EXPECT_TRUE
(
ret_load_conf
);
EXPECT_TRUE
(
conf_
.
IsInitialized
());
CHECK
(
apollo
::
common
::
util
::
GetProtoFromFile
(
conf_file
,
&
conf_
))
<<
"Failed to load "
<<
conf_file
;
manager_
->
Init
(
conf_
);
...
...
modules/prediction/evaluator/vehicle/mlp_evaluator.cc
浏览文件 @
16cff894
...
...
@@ -14,15 +14,16 @@
* limitations under the License.
*****************************************************************************/
#include "modules/prediction/evaluator/vehicle/mlp_evaluator.h"
#include <cmath>
#include <numeric>
#include "modules/prediction/evaluator/vehicle/mlp_evaluator.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/common/math/math_utils.h"
#include "modules/prediction/common/prediction_util.h"
#include "modules/map/proto/map_lane.pb.h"
#include "modules/common/util/file.h"
#include "modules/map/proto/map_lane.pb.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/prediction/common/prediction_util.h"
namespace
apollo
{
namespace
prediction
{
...
...
@@ -80,11 +81,12 @@ void MLPEvaluator::ExtractFeatureValues(Obstacle* obstacle_ptr,
feature_values_
.
clear
();
int
id
=
obstacle_ptr
->
id
();
std
::
vector
<
double
>
obstacle_feature_values
;
if
(
obstacle_feature_values_map_
.
find
(
id
)
==
obstacle_feature_values_map_
.
end
())
{
auto
it
=
obstacle_feature_values_map_
.
find
(
id
);
if
(
it
==
obstacle_feature_values_map_
.
end
())
{
SetObstacleFeatureValues
(
obstacle_ptr
,
&
obstacle_feature_values
);
}
else
{
obstacle_feature_values
=
obstacle_feature_values_map_
[
id
]
;
obstacle_feature_values
=
it
->
second
;
}
if
(
obstacle_feature_values
.
size
()
!=
OBSTACLE_FEATURE_SIZE
)
{
...
...
modules/prediction/evaluator/vehicle/mlp_evaluator.h
浏览文件 @
16cff894
...
...
@@ -17,15 +17,15 @@
#ifndef MODULES_PREDICTION_EVALUATOR_VEHICLE_MLP_EVALUATOR_H_
#define MODULES_PREDICTION_EVALUATOR_VEHICLE_MLP_EVALUATOR_H_
#include <vector>
#include <unordered_map>
#include <string>
#include <memory>
#include <string>
#include <unordered_map>
#include <vector>
#include "modules/prediction/evaluator/evaluator.h"
#include "modules/prediction/container/obstacles/obstacle.h"
#include "modules/prediction/
proto/lane_graph.pb
.h"
#include "modules/prediction/
evaluator/evaluator
.h"
#include "modules/prediction/proto/fnn_vehicle_model.pb.h"
#include "modules/prediction/proto/lane_graph.pb.h"
namespace
apollo
{
namespace
prediction
{
...
...
modules/prediction/evaluator/vehicle/mlp_evaluator_test.cc
浏览文件 @
16cff894
...
...
@@ -21,21 +21,21 @@
#include "gtest/gtest.h"
#include "modules/perception/proto/perception_obstacle.pb.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/common/util/file.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/prediction/container/obstacles/obstacle.h"
#include "modules/prediction/container/obstacles/obstacles_container.h"
#include "modules/perception/proto/perception_obstacle.pb.h"
namespace
apollo
{
namespace
prediction
{
class
MLPEvaluatorTest
:
public
::
testing
::
Test
{
public:
v
irtual
void
SetUp
()
{
v
oid
SetUp
()
override
{
std
::
string
file
=
"modules/prediction/testdata/single_perception_vehicle_onlane.pb.txt"
;
apollo
::
common
::
util
::
GetProtoFromFile
(
file
,
&
perception_obstacles_
);
CHECK
(
apollo
::
common
::
util
::
GetProtoFromFile
(
file
,
&
perception_obstacles_
)
);
FLAGS_map_file
=
"modules/prediction/testdata/kml_map.bin"
;
}
protected:
...
...
modules/prediction/prediction.cc
浏览文件 @
16cff894
...
...
@@ -69,11 +69,8 @@ Status Prediction::Init() {
EvaluatorManager
::
instance
()
->
Init
(
prediction_conf_
);
PredictorManager
::
instance
()
->
Init
(
prediction_conf_
);
CHECK
(
AdapterManager
::
GetLocalization
())
<<
"Localization is not ready."
;
CHECK
(
AdapterManager
::
GetPerceptionObstacles
())
<<
"Perception is not ready."
;
CHECK
(
AdapterManager
::
GetLocalization
())
<<
"Localization is not ready."
;
CHECK
(
AdapterManager
::
GetPerceptionObstacles
())
<<
"Perception is not ready."
;
// Set perception obstacle callback function
AdapterManager
::
SetPerceptionObstaclesCallback
(
&
Prediction
::
OnPerception
,
...
...
modules/prediction/predictor/pedestrian/regional_predictor.cc
浏览文件 @
16cff894
...
...
@@ -14,11 +14,12 @@
* limitations under the License.
*****************************************************************************/
#include <limits>
#include "modules/prediction/predictor/pedestrian/regional_predictor.h"
#include <cmath>
#include <limits>
#include <utility>
#include "modules/prediction/predictor/pedestrian/regional_predictor.h"
#include "modules/prediction/common/prediction_util.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/common/math/kalman_filter.h"
...
...
modules/prediction/predictor/predictor.cc
浏览文件 @
16cff894
...
...
@@ -32,19 +32,14 @@ int Predictor::GetTrajectorySize() {
void
Predictor
::
GenerateTrajectory
(
const
std
::
vector
<::
apollo
::
common
::
TrajectoryPoint
>&
points
,
Trajectory
*
trajectory
)
{
if
(
points
.
size
()
<=
0
)
{
return
;
}
for
(
const
auto
&
point
:
points
)
{
trajectory
->
add_trajectory_point
()
->
CopyFrom
(
point
);
}
trajectory
->
mutable_trajectory_point
()
->
MergeFrom
(
{
points
.
begin
(),
points
.
end
()});
}
void
Predictor
::
SetEqualProbability
(
double
probability
,
int
start_index
)
{
int
num
=
GetTrajectorySize
();
if
(
start_index
>=
0
&&
num
>
0
&&
num
>
start_index
)
{
probability
=
probability
/
static_cast
<
double
>
(
num
-
start_index
);
if
(
start_index
>=
0
&&
num
>
start_index
)
{
probability
/=
static_cast
<
double
>
(
num
-
start_index
);
for
(
int
i
=
start_index
;
i
<
num
;
++
i
)
{
prediction_obstacle_
.
mutable_trajectory
(
i
)
->
set_probability
(
probability
);
}
...
...
modules/prediction/predictor/predictor_factory.cc
浏览文件 @
16cff894
...
...
@@ -16,10 +16,9 @@
#include "modules/prediction/predictor/predictor_factory.h"
#include "modules/prediction/predictor/vehicle/lane_sequence_predictor.h"
#include "modules/prediction/predictor/vehicle/free_move_predictor.h"
#include "modules/common/log.h"
#include "modules/prediction/predictor/vehicle/free_move_predictor.h"
#include "modules/prediction/predictor/vehicle/lane_sequence_predictor.h"
namespace
apollo
{
namespace
prediction
{
...
...
modules/prediction/predictor/predictor_manager.cc
浏览文件 @
16cff894
...
...
@@ -14,10 +14,10 @@
* limitations under the License.
*****************************************************************************/
#include <memory>
#include "modules/prediction/predictor/predictor_manager.h"
#include <memory>
#include "modules/prediction/predictor/vehicle/lane_sequence_predictor.h"
#include "modules/prediction/predictor/vehicle/free_move_predictor.h"
#include "modules/prediction/predictor/pedestrian/regional_predictor.h"
...
...
@@ -80,15 +80,11 @@ void PredictorManager::Init(const PredictionConf& config) {
Predictor
*
PredictorManager
::
GetPredictor
(
const
ObstacleConf
::
PredictorType
&
type
)
{
if
(
predictors_
.
find
(
type
)
!=
predictors_
.
end
())
{
return
predictors_
[
type
].
get
();
}
else
{
return
nullptr
;
}
auto
it
=
predictors_
.
find
(
type
);
return
it
!=
predictors_
.
end
()
?
it
->
second
.
get
()
:
nullptr
;
}
void
PredictorManager
::
Run
(
const
PerceptionObstacles
&
perception_obstacles
)
{
void
PredictorManager
::
Run
(
const
PerceptionObstacles
&
perception_obstacles
)
{
prediction_obstacles_
.
Clear
();
ObstaclesContainer
*
container
=
dynamic_cast
<
ObstaclesContainer
*>
(
ContainerManager
::
instance
()
->
GetContainer
(
...
...
modules/prediction/predictor/predictor_manager.h
浏览文件 @
16cff894
...
...
@@ -22,7 +22,6 @@
#ifndef MODULES_PREDICTION_PREDICTOR_PREDICTOR_MANAGER_H_
#define MODULES_PREDICTION_PREDICTOR_PREDICTOR_MANAGER_H_
#include <unordered_map>
#include <map>
#include <memory>
...
...
@@ -92,8 +91,7 @@ class PredictorManager {
void
RegisterPredictors
();
private:
std
::
map
<
ObstacleConf
::
PredictorType
,
std
::
unique_ptr
<
Predictor
>>
predictors_
;
std
::
map
<
ObstacleConf
::
PredictorType
,
std
::
unique_ptr
<
Predictor
>>
predictors_
;
ObstacleConf
::
PredictorType
vehicle_on_lane_predictor_
=
ObstacleConf
::
LANE_SEQUENCE_PREDICTOR
;
...
...
modules/prediction/predictor/predictor_manager_test.cc
浏览文件 @
16cff894
...
...
@@ -14,11 +14,11 @@
* limitations under the License.
*****************************************************************************/
#include "modules/prediction/predictor/predictor_manager.h"
#include <string>
#include "gtest/gtest.h"
#include "modules/prediction/predictor/predictor_manager.h"
#include "modules/prediction/proto/prediction_conf.pb.h"
#include "modules/common/util/file.h"
...
...
@@ -27,7 +27,7 @@ namespace prediction {
class
PredictorManagerTest
:
public
::
testing
::
Test
{
public:
v
irtual
void
SetUp
()
{
v
oid
SetUp
()
override
{
manager_
=
PredictorManager
::
instance
();
}
...
...
@@ -38,10 +38,8 @@ class PredictorManagerTest : public ::testing::Test {
TEST_F
(
PredictorManagerTest
,
GetPredictor
)
{
std
::
string
conf_file
=
"modules/prediction/testdata/prediction_conf.pb.txt"
;
bool
ret_load_conf
=
::
apollo
::
common
::
util
::
GetProtoFromFile
(
conf_file
,
&
conf_
);
EXPECT_TRUE
(
ret_load_conf
);
EXPECT_TRUE
(
conf_
.
IsInitialized
());
CHECK
(
apollo
::
common
::
util
::
GetProtoFromFile
(
conf_file
,
&
conf_
))
<<
"Failed to load "
<<
conf_file
;
manager_
->
Init
(
conf_
);
...
...
modules/prediction/predictor/vehicle/free_move_predictor.cc
浏览文件 @
16cff894
...
...
@@ -16,10 +16,10 @@
#include "modules/prediction/predictor/vehicle/free_move_predictor.h"
#include <vector>
#include <cmath>
#include <limits>
#include <utility>
#include <vector>
#include "Eigen/Dense"
#include "modules/prediction/common/prediction_gflags.h"
...
...
modules/prediction/predictor/vehicle/free_move_predictor_test.cc
浏览文件 @
16cff894
...
...
@@ -36,7 +36,7 @@ class FreeMovePredictorTest : public ::testing::Test {
virtual
void
SetUp
()
{
std
::
string
file
=
"modules/prediction/testdata/single_perception_vehicle_offlane.pb.txt"
;
apollo
::
common
::
util
::
GetProtoFromFile
(
file
,
&
perception_obstacles_
);
CHECK
(
apollo
::
common
::
util
::
GetProtoFromFile
(
file
,
&
perception_obstacles_
)
);
FLAGS_map_file
=
"modules/prediction/testdata/kml_map.bin"
;
FLAGS_p_var
=
0.1
;
FLAGS_q_var
=
0.01
;
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录