Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
c2fbc052
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 搜索 >>
提交
c2fbc052
编写于
4月 16, 2018
作者:
L
Liangliang Zhang
提交者:
Jiangtao Hu
4月 17, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Planning and Common: fixed namespace issues.
上级
4cef0a22
变更
17
隐藏空白更改
内联
并排
Showing
17 changed file
with
81 addition
and
79 deletion
+81
-79
modules/common/math/cartesian_frenet_conversion.cc
modules/common/math/cartesian_frenet_conversion.cc
+6
-6
modules/common/math/cartesian_frenet_conversion.h
modules/common/math/cartesian_frenet_conversion.h
+6
-4
modules/common/math/cartesian_frenet_conversion_test.cc
modules/common/math/cartesian_frenet_conversion_test.cc
+4
-2
modules/common/math/path_matcher.cc
modules/common/math/path_matcher.cc
+9
-12
modules/common/math/path_matcher.h
modules/common/math/path_matcher.h
+11
-11
modules/planning/common/path/path_data.cc
modules/planning/common/path/path_data.cc
+2
-1
modules/planning/constraint_checker/collision_checker.cc
modules/planning/constraint_checker/collision_checker.cc
+5
-4
modules/planning/constraint_checker/collision_checker.h
modules/planning/constraint_checker/collision_checker.h
+2
-4
modules/planning/lattice/behavior/path_time_graph.cc
modules/planning/lattice/behavior/path_time_graph.cc
+3
-2
modules/planning/lattice/behavior/path_time_graph.h
modules/planning/lattice/behavior/path_time_graph.h
+2
-5
modules/planning/lattice/behavior/prediction_querier.cc
modules/planning/lattice/behavior/prediction_querier.cc
+3
-5
modules/planning/lattice/trajectory_generation/end_condition_sampler.cc
...ng/lattice/trajectory_generation/end_condition_sampler.cc
+6
-9
modules/planning/lattice/trajectory_generation/trajectory_combiner.cc
...ning/lattice/trajectory_generation/trajectory_combiner.cc
+3
-2
modules/planning/lattice/trajectory_generation/trajectory_evaluator.cc
...ing/lattice/trajectory_generation/trajectory_evaluator.cc
+1
-0
modules/planning/planner/lattice/lattice_planner.cc
modules/planning/planner/lattice/lattice_planner.cc
+13
-10
modules/planning/tasks/dp_poly_path/dp_road_graph.cc
modules/planning/tasks/dp_poly_path/dp_road_graph.cc
+1
-0
modules/planning/tasks/qp_spline_path/qp_spline_path_generator.cc
...planning/tasks/qp_spline_path/qp_spline_path_generator.cc
+4
-2
未找到文件。
modules/common/math/cartesian_frenet_conversion.cc
浏览文件 @
c2fbc052
...
...
@@ -22,9 +22,8 @@
#include "modules/common/math/math_utils.h"
namespace
apollo
{
namespace
planning
{
using
apollo
::
common
::
math
::
Vec2d
;
namespace
common
{
namespace
math
{
void
CartesianFrenetConverter
::
cartesian_to_frenet
(
const
double
rs
,
const
double
rx
,
const
double
ry
,
const
double
rtheta
,
...
...
@@ -108,7 +107,7 @@ void CartesianFrenetConverter::frenet_to_cartesian(
const
double
delta_theta
=
std
::
atan2
(
d_condition
[
1
],
one_minus_kappa_r_d
);
const
double
cos_delta_theta
=
std
::
cos
(
delta_theta
);
*
ptr_theta
=
common
::
math
::
NormalizeAngle
(
delta_theta
+
rtheta
);
*
ptr_theta
=
NormalizeAngle
(
delta_theta
+
rtheta
);
const
double
kappa_r_d_prime
=
rdkappa
*
d_condition
[
0
]
+
rkappa
*
d_condition
[
1
];
...
...
@@ -135,7 +134,7 @@ double CartesianFrenetConverter::CalculateTheta(const double rtheta,
const
double
rkappa
,
const
double
l
,
const
double
dl
)
{
return
common
::
math
::
NormalizeAngle
(
rtheta
+
std
::
atan2
(
dl
,
1
-
l
*
rkappa
));
return
NormalizeAngle
(
rtheta
+
std
::
atan2
(
dl
,
1
-
l
*
rkappa
));
}
double
CartesianFrenetConverter
::
CalculateKappa
(
const
double
rkappa
,
...
...
@@ -186,5 +185,6 @@ double CartesianFrenetConverter::CalculateSecondOrderLateralDerivative(
return
res
;
}
}
// namespace planning
}
// namespace math
}
// namespace common
}
// namespace apollo
modules/common/math/cartesian_frenet_conversion.h
浏览文件 @
c2fbc052
...
...
@@ -26,7 +26,8 @@
#include "modules/common/math/vec2d.h"
namespace
apollo
{
namespace
planning
{
namespace
common
{
namespace
math
{
// Notations:
// s_condition = [s, s_dot, s_ddot]
...
...
@@ -84,8 +85,8 @@ class CartesianFrenetConverter {
const
double
l
,
const
double
dl
,
const
double
ddl
);
static
common
::
math
::
Vec2d
CalculateCartesianPoint
(
const
double
rtheta
,
const
common
::
math
::
Vec2d
&
rpoint
,
const
double
l
);
static
Vec2d
CalculateCartesianPoint
(
const
double
rtheta
,
const
Vec2d
&
rpoint
,
const
double
l
);
/**
* @brief: given sl, theta, and road's theta, kappa, extract derivative l,
*second order derivative l:
...
...
@@ -100,7 +101,8 @@ class CartesianFrenetConverter {
const
double
kappa
,
const
double
dkappa_ref
,
const
double
l
);
};
}
// namespace planning
}
// namespace math
}
// namespace common
}
// namespace apollo
#endif // MODULES_COMMON_MATH_CARTESIAN_FRENET_CONVERSION_H_
modules/common/math/cartesian_frenet_conversion_test.cc
浏览文件 @
c2fbc052
...
...
@@ -22,7 +22,8 @@
#include "gtest/gtest.h"
namespace
apollo
{
namespace
planning
{
namespace
common
{
namespace
math
{
TEST
(
TestCartesianFrenetConversion
,
cartesian_to_frenet_test
)
{
double
rs
=
10.0
;
...
...
@@ -64,5 +65,6 @@ TEST(TestCartesianFrenetConversion, cartesian_to_frenet_test) {
EXPECT_NEAR
(
a
,
a_out
,
1.0e-6
);
}
}
// namespace planning
}
// namespace math
}
// namespace common
}
// namespace apollo
modules/common/math/path_matcher.cc
浏览文件 @
c2fbc052
...
...
@@ -28,14 +28,11 @@
#include "modules/common/math/linear_interpolation.h"
namespace
apollo
{
namespace
planning
{
namespace
common
{
namespace
math
{
using
apollo
::
common
::
PathPoint
;
using
apollo
::
common
::
math
::
InterpolateUsingLinearApproximation
;
PathPoint
PathMatcher
::
MatchToPath
(
const
std
::
vector
<
PathPoint
>&
reference_line
,
const
double
x
,
const
double
y
)
{
PathPoint
PathMatcher
::
MatchToPath
(
const
std
::
vector
<
PathPoint
>&
reference_line
,
const
double
x
,
const
double
y
)
{
CHECK_GT
(
reference_line
.
size
(),
0
);
auto
func_distance_square
=
[](
const
PathPoint
&
point
,
const
double
x
,
...
...
@@ -85,8 +82,8 @@ std::pair<double, double> PathMatcher::GetPathFrenetCoordinate(
return
relative_coordinate
;
}
PathPoint
PathMatcher
::
MatchToPath
(
const
std
::
vector
<
PathPoint
>&
reference_line
,
const
double
s
)
{
PathPoint
PathMatcher
::
MatchToPath
(
const
std
::
vector
<
PathPoint
>&
reference_line
,
const
double
s
)
{
auto
comp
=
[](
const
PathPoint
&
point
,
const
double
s
)
{
return
point
.
s
()
<
s
;
};
...
...
@@ -105,8 +102,7 @@ PathPoint PathMatcher::MatchToPath(
}
PathPoint
PathMatcher
::
FindProjectionPoint
(
const
PathPoint
&
p0
,
const
PathPoint
&
p1
,
const
double
x
,
const
PathPoint
&
p1
,
const
double
x
,
const
double
y
)
{
double
v0x
=
x
-
p0
.
x
();
double
v0y
=
y
-
p0
.
y
();
...
...
@@ -121,5 +117,6 @@ PathPoint PathMatcher::FindProjectionPoint(const PathPoint& p0,
return
InterpolateUsingLinearApproximation
(
p0
,
p1
,
p0
.
s
()
+
delta_s
);
}
}
// namespace planning
}
// namespace math
}
// namespace common
}
// namespace apollo
modules/common/math/path_matcher.h
浏览文件 @
c2fbc052
...
...
@@ -27,30 +27,30 @@
#include "modules/common/proto/pnc_point.pb.h"
namespace
apollo
{
namespace
planning
{
namespace
common
{
namespace
math
{
class
PathMatcher
{
public:
PathMatcher
()
=
delete
;
static
common
::
PathPoint
MatchToPath
(
const
std
::
vector
<
common
::
PathPoint
>&
reference_line
,
const
double
x
,
const
double
y
);
static
PathPoint
MatchToPath
(
const
std
::
vector
<
PathPoint
>&
reference_line
,
const
double
x
,
const
double
y
);
static
std
::
pair
<
double
,
double
>
GetPathFrenetCoordinate
(
const
std
::
vector
<
common
::
PathPoint
>&
reference_line
,
const
double
x
,
const
std
::
vector
<
PathPoint
>&
reference_line
,
const
double
x
,
const
double
y
);
static
common
::
PathPoint
MatchToPath
(
const
std
::
vector
<
common
::
PathPoint
>&
reference_line
,
const
double
s
);
static
PathPoint
MatchToPath
(
const
std
::
vector
<
PathPoint
>&
reference_line
,
const
double
s
);
private:
static
common
::
PathPoint
FindProjectionPoint
(
const
common
::
PathPoint
&
p0
,
const
common
::
PathPoint
&
p1
,
const
double
x
,
const
double
y
);
static
PathPoint
FindProjectionPoint
(
const
PathPoint
&
p0
,
const
PathPoint
&
p1
,
const
double
x
,
const
double
y
);
};
}
// namespace planning
}
// namespace math
}
// namespace common
}
// namespace apollo
#endif // MODULES_COMMON_MATH_PATH_MATCHER_H_
modules/planning/common/path/path_data.cc
浏览文件 @
c2fbc052
...
...
@@ -34,8 +34,9 @@
namespace
apollo
{
namespace
planning
{
using
apollo
::
common
::
SLPoint
;
using
apollo
::
common
::
math
::
CartesianFrenetConverter
;
using
apollo
::
common
::
math
::
Vec2d
;
using
apollo
::
common
::
SLPoint
;
bool
PathData
::
SetDiscretizedPath
(
const
DiscretizedPath
&
path
)
{
if
(
reference_line_
==
nullptr
)
{
...
...
modules/planning/constraint_checker/collision_checker.cc
浏览文件 @
c2fbc052
...
...
@@ -15,7 +15,7 @@
*****************************************************************************/
/**
* @file
collision_checker.cpp
* @file
**/
#include "modules/planning/constraint_checker/collision_checker.h"
...
...
@@ -34,10 +34,11 @@
namespace
apollo
{
namespace
planning
{
using
apollo
::
common
::
PathPoint
;
using
apollo
::
common
::
TrajectoryPoint
;
using
apollo
::
common
::
math
::
Box2d
;
using
apollo
::
common
::
math
::
PathMatcher
;
using
apollo
::
common
::
math
::
Vec2d
;
using
apollo
::
common
::
PathPoint
;
using
apollo
::
common
::
TrajectoryPoint
;
CollisionChecker
::
CollisionChecker
(
const
std
::
vector
<
const
Obstacle
*>&
obstacles
,
const
double
ego_vehicle_s
,
...
...
@@ -61,7 +62,7 @@ bool CollisionChecker::InCollision(
double
ego_theta
=
trajectory_point
.
path_point
().
theta
();
Box2d
ego_box
(
{
trajectory_point
.
path_point
().
x
(),
trajectory_point
.
path_point
().
y
()},
ego_theta
,
ego_length
,
ego_width
);
ego_theta
,
ego_length
,
ego_width
);
double
shift_distance
=
ego_length
/
2.0
-
vehicle_config
.
vehicle_param
().
back_edge_to_center
();
Vec2d
shift_vec
{
shift_distance
*
std
::
cos
(
ego_theta
),
...
...
modules/planning/constraint_checker/collision_checker.h
浏览文件 @
c2fbc052
...
...
@@ -34,8 +34,7 @@ namespace planning {
class
CollisionChecker
{
public:
explicit
CollisionChecker
(
const
std
::
vector
<
const
Obstacle
*>&
obstacles
,
const
double
ego_vehicle_s
,
const
std
::
vector
<
const
Obstacle
*>&
obstacles
,
const
double
ego_vehicle_s
,
const
double
ego_vehicle_d
,
const
std
::
vector
<
common
::
PathPoint
>&
discretized_reference_line
);
...
...
@@ -43,8 +42,7 @@ class CollisionChecker {
private:
void
BuildPredictedEnvironment
(
const
std
::
vector
<
const
Obstacle
*>&
obstacles
,
const
double
ego_vehicle_s
,
const
std
::
vector
<
const
Obstacle
*>&
obstacles
,
const
double
ego_vehicle_s
,
const
double
ego_vehicle_d
,
const
std
::
vector
<
common
::
PathPoint
>&
discretized_reference_line
);
...
...
modules/planning/lattice/behavior/path_time_graph.cc
浏览文件 @
c2fbc052
...
...
@@ -35,11 +35,12 @@
namespace
apollo
{
namespace
planning
{
using
apollo
::
common
::
math
::
lerp
;
using
apollo
::
common
::
math
::
Box2d
;
using
apollo
::
common
::
math
::
PathMatcher
;
using
apollo
::
common
::
PathPoint
;
using
apollo
::
common
::
TrajectoryPoint
;
using
apollo
::
common
::
math
::
Box2d
;
using
apollo
::
perception
::
PerceptionObstacle
;
using
apollo
::
common
::
math
::
lerp
;
PathTimeGraph
::
PathTimeGraph
(
const
std
::
vector
<
const
Obstacle
*>&
obstacles
,
...
...
modules/planning/lattice/behavior/path_time_graph.h
浏览文件 @
c2fbc052
...
...
@@ -41,11 +41,8 @@ class PathTimeGraph {
public:
PathTimeGraph
(
const
std
::
vector
<
const
Obstacle
*>&
obstacles
,
const
std
::
vector
<
common
::
PathPoint
>&
discretized_ref_points
,
const
double
s_start
,
const
double
s_end
,
const
double
t_start
,
const
double
t_end
,
const
double
path_width
);
const
double
s_start
,
const
double
s_end
,
const
double
t_start
,
const
double
t_end
,
const
double
path_width
);
const
std
::
vector
<
PathTimeObstacle
>&
GetPathTimeObstacles
()
const
;
...
...
modules/planning/lattice/behavior/prediction_querier.cc
浏览文件 @
c2fbc052
...
...
@@ -22,8 +22,8 @@
#include <string>
#include "modules/common/math/path_matcher.h"
#include "modules/common/math/linear_interpolation.h"
#include "modules/common/math/path_matcher.h"
namespace
apollo
{
namespace
planning
{
...
...
@@ -75,9 +75,7 @@ std::vector<const Obstacle*> PredictionQuerier::GetObstacles() const {
}
double
PredictionQuerier
::
ProjectVelocityAlongReferenceLine
(
const
std
::
string
&
obstacle_id
,
const
double
s
,
const
double
t
)
const
{
const
std
::
string
&
obstacle_id
,
const
double
s
,
const
double
t
)
const
{
CHECK
(
id_obstacle_map_
.
find
(
obstacle_id
)
!=
id_obstacle_map_
.
end
());
const
auto
&
trajectory
=
id_obstacle_map_
.
at
(
obstacle_id
)
->
Trajectory
();
...
...
@@ -110,7 +108,7 @@ double PredictionQuerier::ProjectVelocityAlongReferenceLine(
double
v_x
=
v
*
std
::
cos
(
heading
);
double
v_y
=
v
*
std
::
sin
(
heading
);
common
::
PathPoint
obstacle_point_on_ref_line
=
PathMatcher
::
MatchToPath
(
*
ptr_reference_line_
,
s
);
common
::
math
::
PathMatcher
::
MatchToPath
(
*
ptr_reference_line_
,
s
);
double
ref_theta
=
obstacle_point_on_ref_line
.
theta
();
return
std
::
cos
(
ref_theta
)
*
v_x
+
std
::
sin
(
ref_theta
)
*
v_y
;
...
...
modules/planning/lattice/trajectory_generation/end_condition_sampler.cc
浏览文件 @
c2fbc052
...
...
@@ -69,8 +69,7 @@ EndConditionSampler::SampleLonEndConditionsForCruising(
std
::
vector
<
std
::
pair
<
std
::
array
<
double
,
3
>
,
double
>>
end_s_conditions
;
for
(
const
auto
&
time
:
time_samples
)
{
double
v_upper
=
std
::
min
(
feasible_region_
.
VUpper
(
time
),
ref_cruise_speed
);
double
v_upper
=
std
::
min
(
feasible_region_
.
VUpper
(
time
),
ref_cruise_speed
);
double
v_lower
=
feasible_region_
.
VLower
(
time
);
std
::
array
<
double
,
3
>
lower_end_s
=
{
0.0
,
v_lower
,
0.0
};
...
...
@@ -88,8 +87,7 @@ EndConditionSampler::SampleLonEndConditionsForCruising(
if
(
num_of_mid_points
>
0
)
{
double
velocity_seg
=
v_range
/
(
num_of_mid_points
+
1
);
for
(
std
::
size_t
i
=
1
;
i
<=
num_of_mid_points
;
++
i
)
{
std
::
array
<
double
,
3
>
end_s
=
{
0.0
,
v_lower
+
velocity_seg
*
i
,
0.0
};
std
::
array
<
double
,
3
>
end_s
=
{
0.0
,
v_lower
+
velocity_seg
*
i
,
0.0
};
end_s_conditions
.
emplace_back
(
end_s
,
time
);
}
}
...
...
@@ -120,8 +118,8 @@ EndConditionSampler::SampleLonEndConditionsForStopping(
continue
;
}
for
(
const
auto
&
s_offset
:
s_offsets
)
{
std
::
array
<
double
,
3
>
end_s
=
{
std
::
max
(
init_s_
[
0
],
ref_stop_point
+
s_offset
),
0.0
,
0.0
};
std
::
array
<
double
,
3
>
end_s
=
{
std
::
max
(
init_s_
[
0
],
ref_stop_point
+
s_offset
),
0.0
,
0.0
};
end_s_conditions
.
emplace_back
(
end_s
,
time
);
}
}
...
...
@@ -179,7 +177,6 @@ void EndConditionSampler::QueryFollowPathTimePoints(
CHECK_GE
(
FLAGS_num_sample_follow_per_timestamp
,
2
);
double
s_gap
=
FLAGS_default_lon_buffer
/
static_cast
<
double
>
(
FLAGS_num_sample_follow_per_timestamp
);
std
::
vector
<
double
>
sample_s
;
for
(
std
::
size_t
i
=
0
;
i
<
FLAGS_num_sample_follow_per_timestamp
;
++
i
)
{
double
s
=
s_lower
+
s_gap
*
static_cast
<
double
>
(
i
);
SamplePoint
sample_point
;
...
...
@@ -203,8 +200,8 @@ void EndConditionSampler::QueryOvertakePathTimePoints(
obstacle_id
,
path_time_point
.
s
(),
path_time_point
.
t
());
SamplePoint
sample_point
;
sample_point
.
mutable_path_time_point
()
->
CopyFrom
(
path_time_point
);
sample_point
.
mutable_path_time_point
()
->
set_s
(
path_time_point
.
s
()
+
FLAGS_default_lon_buffer
);
sample_point
.
mutable_path_time_point
()
->
set_s
(
path_time_point
.
s
()
+
FLAGS_default_lon_buffer
);
sample_point
.
set_ref_v
(
v
);
sample_points
->
push_back
(
std
::
move
(
sample_point
));
}
...
...
modules/planning/lattice/trajectory_generation/trajectory_combiner.cc
浏览文件 @
c2fbc052
...
...
@@ -25,6 +25,8 @@
namespace
apollo
{
namespace
planning
{
using
apollo
::
common
::
math
::
CartesianFrenetConverter
;
using
apollo
::
common
::
math
::
PathMatcher
;
using
apollo
::
common
::
PathPoint
;
using
apollo
::
common
::
TrajectoryPoint
;
...
...
@@ -57,8 +59,7 @@ DiscretizedTrajectory TrajectoryCombiner::Combine(
double
d_prime
=
lat_trajectory
.
Evaluate
(
1
,
s_param
);
double
d_pprime
=
lat_trajectory
.
Evaluate
(
2
,
s_param
);
PathPoint
matched_ref_point
=
PathMatcher
::
MatchToPath
(
reference_line
,
s
);
PathPoint
matched_ref_point
=
PathMatcher
::
MatchToPath
(
reference_line
,
s
);
double
x
=
0.0
;
double
y
=
0.0
;
...
...
modules/planning/lattice/trajectory_generation/trajectory_evaluator.cc
浏览文件 @
c2fbc052
...
...
@@ -36,6 +36,7 @@ namespace apollo {
namespace
planning
{
using
Trajectory1d
=
Curve1d
;
using
apollo
::
common
::
math
::
PathMatcher
;
using
apollo
::
common
::
FrenetFramePoint
;
using
apollo
::
common
::
PathPoint
;
using
apollo
::
common
::
SpeedPoint
;
...
...
modules/planning/planner/lattice/lattice_planner.cc
浏览文件 @
c2fbc052
...
...
@@ -51,6 +51,8 @@ using apollo::common::PathPoint;
using
apollo
::
common
::
Status
;
using
apollo
::
common
::
TrajectoryPoint
;
using
apollo
::
common
::
adapter
::
AdapterManager
;
using
apollo
::
common
::
math
::
PathMatcher
;
using
apollo
::
common
::
math
::
CartesianFrenetConverter
;
using
apollo
::
common
::
time
::
Clock
;
namespace
{
...
...
@@ -275,7 +277,8 @@ Status LatticePlanner::PlanOnReferenceLine(
std
::
vector
<
common
::
SpeedPoint
>
lon_future_trajectory
;
std
::
vector
<
common
::
FrenetFramePoint
>
lat_future_trajectory
;
if
(
!
MapFutureTrajectoryToSL
(
future_trajectory
,
*
ptr_reference_line
,
&
lon_future_trajectory
,
&
lat_future_trajectory
))
{
&
lon_future_trajectory
,
&
lat_future_trajectory
))
{
AERROR
<<
"Auto tuning failed since no mapping "
<<
"from future trajectory to lon-lat"
;
}
...
...
@@ -287,22 +290,22 @@ Status LatticePlanner::PlanOnReferenceLine(
// 4. emit
planning_internal
::
PlanningData
*
ptr_debug
=
reference_line_info
->
mutable_debug
()
->
mutable_planning_data
();
reference_line_info
->
mutable_debug
()
->
mutable_planning_data
();
apollo
::
planning_internal
::
AutoTuningTrainingData
auto_tuning_data
;
for
(
double
student_cost_component
:
trajectory_pair_cost_components
)
{
auto_tuning_data
.
mutable_student_component
()
->
add_cost_component
(
student_cost_component
);
auto_tuning_data
.
mutable_student_component
()
->
add_cost_component
(
student_cost_component
);
}
for
(
double
teacher_cost_component
:
future_traj_component_cost
)
{
auto_tuning_data
.
mutable_teacher_component
()
->
add_cost_component
(
teacher_cost_component
);
auto_tuning_data
.
mutable_teacher_component
()
->
add_cost_component
(
teacher_cost_component
);
}
ptr_debug
->
mutable_auto_tuning_training_data
()
->
CopyFrom
(
auto_tuning_data
);
ptr_debug
->
mutable_auto_tuning_training_data
()
->
CopyFrom
(
auto_tuning_data
);
}
// Print the chosen end condition and start condition
...
...
@@ -413,10 +416,10 @@ bool LatticePlanner::MapFutureTrajectoryToSL(
return
false
;
}
for
(
const
common
::
TrajectoryPoint
&
trajectory_point
:
future_trajectory
.
trajectory_points
())
{
future_trajectory
.
trajectory_points
())
{
const
PathPoint
&
path_point
=
trajectory_point
.
path_point
();
PathPoint
matched_point
=
PathMatcher
::
MatchToPath
(
discretized_reference_line
,
path_point
.
x
(),
path_point
.
y
());
discretized_reference_line
,
path_point
.
x
(),
path_point
.
y
());
std
::
array
<
double
,
3
>
pose_s
;
std
::
array
<
double
,
3
>
pose_d
;
ComputeInitFrenetState
(
matched_point
,
trajectory_point
,
&
pose_s
,
&
pose_d
);
...
...
modules/planning/tasks/dp_poly_path/dp_road_graph.cc
浏览文件 @
c2fbc052
...
...
@@ -42,6 +42,7 @@ namespace planning {
using
apollo
::
common
::
ErrorCode
;
using
apollo
::
common
::
Status
;
using
apollo
::
common
::
math
::
CartesianFrenetConverter
;
DPRoadGraph
::
DPRoadGraph
(
const
DpPolyPathConfig
&
config
,
const
ReferenceLineInfo
&
reference_line_info
,
...
...
modules/planning/tasks/qp_spline_path/qp_spline_path_generator.cc
浏览文件 @
c2fbc052
...
...
@@ -29,14 +29,15 @@
#include "modules/common/log.h"
#include "modules/common/macro.h"
#include "modules/common/math/cartesian_frenet_conversion.h"
#include "modules/common/util/string_util.h"
#include "modules/common/util/util.h"
#include "modules/common/math/cartesian_frenet_conversion.h"
#include "modules/planning/common/planning_gflags.h"
#include "modules/planning/common/planning_util.h"
namespace
apollo
{
namespace
planning
{
namespace
{
double
GetLaneChangeLateralShift
(
const
double
v
)
{
const
double
l0
=
2.0
;
// shift at v = 0 m/s
...
...
@@ -48,7 +49,8 @@ double GetLaneChangeLateralShift(const double v) {
}
}
// namespace
using
Vec2d
=
apollo
::
common
::
math
::
Vec2d
;
using
apollo
::
common
::
math
::
CartesianFrenetConverter
;
using
apollo
::
common
::
math
::
Vec2d
;
QpSplinePathGenerator
::
QpSplinePathGenerator
(
Spline1dGenerator
*
spline_generator
,
const
ReferenceLine
&
reference_line
,
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录