目录
1、void TopologyPRM::init(ros::NodeHandle& nh)
2、void TopologyPRM::findTopoPaths()
3、list TopologyPRM::createGraph()
3.2 dist = edt_environment_->evaluateCoarseEDT(pt, -1.0)
3.3 vector TopologyPRM::findVisibGuard()
3.4 bool TopologyPRM::needConnection()
3.4.1 判断同伦:使用函数bool TopologyPRM::sameTopoPath()
3.5 void TopologyPRM::pruneGraph()
4、vector> TopologyPRM::searchPaths()
4.1深度优先搜索算法DFS:void TopologyPRM::depthFirstSearch()
5、void TopologyPRM::shortcutPaths()
5.1 void TopologyPRM::shortcutPath() 路径缩短
5.1.1 vector TopologyPRM::discretizeLine()
6、vector> TopologyPRM::pruneEquivalent()
7、vector> TopologyPRM::selectShortPaths()
该函数用于初始化所有参数
- void TopologyPRM::init(ros::NodeHandle& nh) {
- //初始化
- graph_.clear();//图
- eng_ = default_random_engine(rd_());//默认随机数生成器
- rand_pos_ = uniform_real_distribution<double>(-1.0, 1.0);//均匀实分布
-
- // init parameter初始化参数
- nh.param("topo_prm/sample_inflate_x", sample_inflate_(0), -1.0);//inflate膨胀
- nh.param("topo_prm/sample_inflate_y", sample_inflate_(1), -1.0);
- nh.param("topo_prm/sample_inflate_z", sample_inflate_(2), -1.0);
- nh.param("topo_prm/clearance", clearance_, -1.0);//安全阈值
- nh.param("topo_prm/short_cut_num", short_cut_num_, -1);//短_修剪数目
- nh.param("topo_prm/reserve_num", reserve_num_, -1);//保留的数目
- nh.param("topo_prm/ratio_to_short", ratio_to_short_, -1.0);//长度比值
- nh.param("topo_prm/max_sample_num", max_sample_num_, -1);//最大采样数目
- nh.param("topo_prm/max_sample_time", max_sample_time_, -1.0);//最大采样时间
- nh.param("topo_prm/max_raw_path", max_raw_path_, -1);//最大偏航路径
- nh.param("topo_prm/max_raw_path2", max_raw_path2_, -1);//最大偏航路径2
- nh.param("topo_prm/parallel_shortcut", parallel_shortcut_, false);//并行剪枝
- resolution_ = edt_environment_->sdf_map_->getResolution();//分辨率
- offset_ = Eigen::Vector3d(0.5, 0.5, 0.5) - edt_environment_->sdf_map_->getOrigin() / resolution_;//偏差
-
- for (int i = 0; i < max_raw_path_; ++i) {
- casters_.push_back(RayCaster());//光线投射
- }
- }
该函数用于寻找拓扑路径,即Topopath 路径搜索算法的调用入口,由五部分组成,下面将一一进行分析。
1.createGraph;2.searchPaths; 3.shortcutPaths(); 4.pruneEquivalent();5.selectShortPaths();
- void TopologyPRM::findTopoPaths(Eigen::Vector3d start, Eigen::Vector3d end,
- vector
start_pts, vector end_pts, - list
& graph, vector>& raw_paths, - vector
>& filtered_paths, - vector
>& select_paths) { - //寻找Topo路径(多条)
- ros::Time t1, t2;//时间
-
- double graph_time, search_time, short_time, prune_time, select_time;
- //生成节点图的时间、路径搜索时间、路径缩短时间、路径修剪时间、路径选择时间
- /* ---------- create the topo graph ---------- */
- //创建空间中的采样节点图
- t1 = ros::Time::now();//t1为当前时间
-
- start_pts_ = start_pts;//起始位置
- end_pts_ = end_pts;//目标位置
-
- graph = createGraph(start, end);//生成节点图(以起点和目标点为节点)
-
- graph_time = (ros::Time::now() - t1).toSec();//节点图生成的时间
-
- /* ---------- search paths in the graph ---------- */
- //在节点图中搜索路径
- t1 = ros::Time::now();
-
- raw_paths = searchPaths();//搜索的路径
-
- search_time = (ros::Time::now() - t1).toSec();//搜索时间
-
- /* ---------- path shortening ---------- */
- //路径缩短
- // for parallel, save result in short_paths_
- //对于并行,将结果保存在短_路径 short_paths_中_
- t1 = ros::Time::now();
-
- shortcutPaths();//
-
- short_time = (ros::Time::now() - t1).toSec();//路径缩短时间
-
- /* ---------- prune equivalent paths ---------- */
- //等效路径d的修剪,只保留属于不同UVD class
- t1 = ros::Time::now();
-
- filtered_paths = pruneEquivalent(short_paths_);//已筛选的路径
-
- prune_time = (ros::Time::now() - t1).toSec();//修剪时间
- // cout << "prune: " << (t2 - t1).toSec() << endl;
-
- /* ---------- select N shortest paths ---------- */
- t1 = ros::Time::now();
-
- select_paths = selectShortPaths(filtered_paths, 1);//搜索最佳路径
-
- select_time = (ros::Time::now() - t1).toSec();//搜索时间
-
- final_paths_ = select_paths;//搜索的路径为最终的路径
-
- double total_time = graph_time + search_time + short_time + prune_time + select_time;//总时间的计算
-
- std::cout << "\n[Topo]: total time: " << total_time << ", graph: " << graph_time
- << ", search: " << search_time << ", short: " << short_time << ", prune: " << prune_time
- << ", select: " << select_time << std::endl;
- }
根据起始和目标的位置信息和载入的参数来设置采样点的范围,在采样时间大于最大采样时间或采样点数大于最大采样点数时停止采样。
- list
TopologyPRM::createGraph(Eigen::Vector3d start, Eigen::Vector3d end) { - //创建节点图
- // std::cout << "[Topo]: searching----------------------" << std::endl;
-
- /* init the start, end and sample region */
- //初始化开始、结束和采样区域
- graph_.clear();//清除所有的图节点
- // collis_.clear();
-
- GraphNode::Ptr start_node = GraphNode::Ptr(new GraphNode(start, GraphNode::Guard, 0));//开始节点为开始位置
- GraphNode::Ptr end_node = GraphNode::Ptr(new GraphNode(end, GraphNode::Guard, 1));//结束节点为目标位置
- //开始节点和结束节点加入节点图中
- graph_.push_back(start_node);
- graph_.push_back(end_node);
-
- // sample region采样区域
- sample_r_(0) = 0.5 * (end - start).norm() + sample_inflate_(0);
- //sample_inflate_x为sample_inflate_(0),x方向上采样的半径
- sample_r_(1) = sample_inflate_(1);//y方向上采样的半径
- sample_r_(2) = sample_inflate_(2);//z方向上采样的半径
-
- // transformation转移
- translation_ = 0.5 * (start + end);
-
- Eigen::Vector3d xtf, ytf, ztf, downward(0, 0, -1);
- xtf = (end - translation_).normalized();
- ytf = xtf.cross(downward).normalized();
- ztf = xtf.cross(ytf);
-
- rotation_.col(0) = xtf;
- rotation_.col(1) = ytf;
- rotation_.col(2) = ztf;
-
- int node_id = 1;//节点索引
-
- /* ---------- main loop ---------- */
- //主循环
- int sample_num = 0;//采样数目
- double sample_time = 0.0;//采样时间
- Eigen::Vector3d pt;//位置
- ros::Time t1, t2;//时间
- while (sample_time < max_sample_time_ && sample_num < max_sample_num_) {
- //若采样时间大于最大采样时间,采样点数大于最大采样点数时,结束采样循环
- t1 = ros::Time::now();
-
- pt = getSample();//获取采样
- ++sample_num;//采样数目++
- double dist;//距离
- Eigen::Vector3d grad;//梯度
- // edt_environment_->evaluateEDTWithGrad(pt, -1.0, dist, grad);
- dist = edt_environment_->evaluateCoarseEDT(pt, -1.0);//距离为ESDF地图的离最近障碍物的距离
- if (dist <= clearance_) {//如果距离小于安全阈值
- sample_time += (ros::Time::now() - t1).toSec();//采样时间+,说明采样点在障碍物中
- continue;//结束
- }
-
- /* find visible guard */
- //寻找可见的guard点
- vector
visib_guards = findVisibGuard(pt);//可见的guard点 - if (visib_guards.size() == 0) {//如果可见的guard的数目为0
- GraphNode::Ptr guard = GraphNode::Ptr(new GraphNode(pt, GraphNode::Guard, ++node_id));
- //该节点创建为一个新的guard点
- graph_.push_back(guard);
- } else if (visib_guards.size() == 2) {
- /* try adding new connection between two guard */
- // vector
> sort_guards = - // sortVisibGuard(visib_guards);
- //该采样点(节点)正好对两个guard的可见时
- bool need_connect = needConnection(visib_guards[0], visib_guards[1], pt);
- //利用needConnection函数判断是否要添加新的connector
- if (!need_connect) {
- sample_time += (ros::Time::now() - t1).toSec();//如果不需要连接则采样时间+
- continue;
- }
- // new useful connection needed, add new connector
- //需要新的有用连接,添加新连接器
- GraphNode::Ptr connector = GraphNode::Ptr(new GraphNode(pt, GraphNode::Connector, ++node_id));
- graph_.push_back(connector);//节点图中添加新的连接节点
-
- // connect guards,连接guards点
- visib_guards[0]->neighbors_.push_back(connector);
- visib_guards[1]->neighbors_.push_back(connector);
-
- connector->neighbors_.push_back(visib_guards[0]);
- connector->neighbors_.push_back(visib_guards[1]);
- }
-
- sample_time += (ros::Time::now() - t1).toSec();//采样时间
- }
-
- /* print record */
- std::cout << "[Topo]: sample num: " << sample_num;
-
- pruneGraph();//修剪节点图
- // std::cout << "[Topo]: node num: " << graph_.size() << std::endl;
-
- return graph_;//返回节点图
- // return searchPaths(start_node, end_node);
- }
该函数用于获取采样的节点
- Eigen::Vector3d TopologyPRM::getSample() {
- //获取采样点
- /* sampling */
- Eigen::Vector3d pt;//位置
- pt(0) = rand_pos_(eng_) * sample_r_(0);//x
- pt(1) = rand_pos_(eng_) * sample_r_(1);//y
- pt(2) = rand_pos_(eng_) * sample_r_(2);//z
-
- pt = rotation_ * pt + translation_;//最终位置
-
- return pt;//返回采样节点的位置
- }
用于判断采样的节点是否位于障碍物中,是则continue;
前采样点与任一个guard都不可见时,则把它当做新的guard添加到gragh中,如果有且只有两个可见guard,则要利用needConnection函数判断是否要添加新的connector.
- vector
TopologyPRM::findVisibGuard(Eigen::Vector3d pt) { - //当一个采样点正好对两个guards可见时,创建一个新的connectors
- //发现可见的guards点
- vector
visib_guards;//可见的guards点 - Eigen::Vector3d pc;
-
- int visib_num = 0;//可见的数目
-
- /* find visible GUARD from pt */
- //从pt发现可见的guard点
- for (list
::iterator iter = graph_.begin(); iter != graph_.end(); ++iter) { - //迭代
- if ((*iter)->type_ == GraphNode::Connector) continue;
-
- if (lineVisib(pt, (*iter)->pos_, resolution_, pc)) {
- visib_guards.push_back((*iter));
- ++visib_num;
- if (visib_num > 2) break;
- }
- }
-
- return visib_guards;//返回可见的guard点
- }
将两个节点连接起来,利用利用raycast步进和ESDF中的距离信息来逐步检验连线上是否有障碍物,有障碍物则者两个节点不可见。
- bool TopologyPRM::lineVisib(const Eigen::Vector3d& p1, const Eigen::Vector3d& p2, double thresh,
- Eigen::Vector3d& pc, int caster_id) {
- //linVisb()判断两个guard之间是否可见的。
- //即把两个节点连起来,利用raycast步进和ESDF地图来逐步检验连线上的每一个点是否是障碍物。
-
- Eigen::Vector3d ray_pt;//投射位置
- Eigen::Vector3i pt_id;//位置索引
- double dist;//距离
-
- casters_[caster_id].setInput(p1 / resolution_, p2 / resolution_);//光线投射
- while (casters_[caster_id].step(ray_pt)) {
- pt_id(0) = ray_pt(0) + offset_(0);
- pt_id(1) = ray_pt(1) + offset_(1);
- pt_id(2) = ray_pt(2) + offset_(2);
- dist = edt_environment_->sdf_map_->getDistance(pt_id);//获取距离
- if (dist <= thresh) {//距离小于阈值
- edt_environment_->sdf_map_->indexToPos(pt_id, pc);
- return false;
- }
- }
- return true;
- }
即判断当前路径(可见guard1,当前采样点,可见guard2)为path1,是否与(可见guard1,可见guard2,…)形成的其他路径path2同伦,如果同伦,则要判断path1是否比path2短,如果path1 判断两条路径是否可以连续映射,则使用LinVisb来查看两两映射的点的连接是否在障碍物中,所有点一一映射且无障碍物则为同伦。 修剪无用的采样点,只有只有一个neighbor的guard节点。 通过深度优先搜索算法DFS,在节点图中搜索有用的路径,按节点数目对路径进行排序,选择节点数目较少的路径进行保留,并存储在raw_paths_中。 将上一步保留的raw_paths_路径执行shortcutPath函数,对这些路径进行缩短。 对于一条待缩短的路径,首先利用discretizePath函数将其从几个节点变为更稠密的一系列路径点。然后创建 short_path来存储新的缩短后的路径。对于原始上的每一个点,都与short_path的最后一个点(初始化时为原始路径的起点)连线并利用lineVisb来衡量可见性。若不可见,则将线上不可见的点往外推至一个新的位置。推的方向与连线垂直并和ESDF梯度方共面。并把新的位置点push_back进short_path中。直到结束循环把终点Push_back进short_path中。最后判断当前short_path是否比原来的路径短,若短,则取代原来的路径,若不是,则保持不变。 将整条轨迹从几个节点离散化为更稠密的一系列路径点。 剪枝等效路径,原有路径集中的每一条路径与路径集中的路径进行比较,同伦的路径进行处理,有则不加入已存在路径且删去当前的路径,不同伦则进行保留,加入路径集。 pruneEquivalent后的路径在进行筛选,筛出路径中最短的路径,shortest_path,将路径集中的其它路径与最短路径进行比较,产生一个长度比值,该比值小于一定阈值时,将该路径进行放入新的路径集中保留,直到达到最大路径数目或循环结束。
3.4.1 判断同伦:使用函数bool TopologyPRM::sameTopoPath()
3.5 void TopologyPRM::pruneGraph()
4、vector
4.1深度优先搜索算法DFS:void TopologyPRM::depthFirstSearch()
5、void TopologyPRM::shortcutPaths()
5.1 void TopologyPRM::shortcutPath() 路径缩短
5.1.1 vector
6、vector
7、vector