【Apollo源码分析】系列的第六部分【planning】
planning模块 代码大概有1000行左右。 这个模块仍然处于待完善的状态。
和其他模块一样,这里只有框架,除了 RTKReplayPlanner,没有实用的算法。
planning模块的输入:
- Localization
- Perception (future work)
- Prediction (future work)
- Decision (future work)
- Recorded RTK trajectory
planning模块的输出:
- trajectory point
planning/main.cc
照例先看看main.cc
int main(int argc, char **argv) {
google::InitGoogleLogging(argv[0]);
google::ParseCommandLineFlags(&argc, &argv, true);
ros::init(argc, argv, "planning");
::apollo::planning::PlanningNode planning_node;
planning_node.Run();
return 0;
}
//与#define APOLLO_MAIN(APP) 大同小异。可能后期会改为一致。
planning/common/planning_gflags.h
.h文件和.cc文件,声明和定义planning模块的变量。
主要的变量是:
#include "modules/planning/common/planning_gflags.h"
//发布运动规划planning的频率,单位是HZ。
DEFINE_int32(planning_loop_rate, 5, "Loop rate for planning node");
//用RTK定位算法得到的最近一段时间的历史轨迹
DEFINE_string(rtk_trajectory_filename, "modules/planning/data/garage.csv",
"Loop rate for planning node");
//planning时,用于回退匹配的轨迹节点数量。
DEFINE_uint64(rtk_trajectory_backward, 10,
"The number of points to be included in RTK trajectory "
"before the matched point");
//前向匹配的轨迹节点数量
DEFINE_uint64(rtk_trajectory_forward, 800,
"The number of points to be included in RTK trajectory "
"after the matched point");
//重新规划planning的阈值,高于此值则重新planning
DEFINE_double(replanning_threshold, 2.0,
"The threshold of position deviation "
"that triggers the planner replanning");
//轨迹点之间的时间分辨率/间隔,0.01s
DEFINE_double(trajectory_resolution, 0.01,
"The time resolution of "
"output trajectory.");
planning/planner/planner.h
Planner是纯虚基类。有一个公有的Plan():
纯虚函数。继承它的子类必须重写这个纯虚函数才能实例化。
所有的路径规划的class都继承自这个类。
目的:虚函数指针,运行时决断,父类指针指向子类对象,runtime时调用子类的成员函数。
具体到Planner 而言就是提供一个公有的接口 virtual bool Plan().
使得在运行时可以执行不同的planning算法。
参数1:planning起始点
参数2:路径规划结果集,由一系列离散的轨迹点组成。
目的:根据历史行驶的一系列轨迹节点,
并结合Perception模块+Prediction模块+Decision模块+
Localization地图定位模块,来进行推算未来一段时间的行驶轨迹。
本质上是路径规划算法。
virtual bool Plan