Fast-Planner(五)详解TopologyPRM

本文上接Fast-Planner第一篇文章的内容,本文主要详解这一系列的第二篇Robust Real-time UAV Replanning Using Guided Gradient-based Optimization and Topological Paths中的TopologyPRM即其代码。如有问题,欢迎各位大佬评论指出,带着我一起进步。

1. 简介

这篇文章主要贡献:

  • 为解决GTO(基于梯度的轨迹优化)带来的陷入局部极小值的问题,提出了一种路径引导优化(PGO)来处理局部极小值。
  • 一个有效的拓扑路径搜索算法,适用于与PGO结合,生成多条备选拓扑路径再通过剪枝优化生成有效的重规划轨迹。

GTO仅依赖于ESDF提供的梯度信息时,但是在下图这类“谷”和“脊”等位置梯度发生突变,这导致目标函数将轨迹朝着不同方向推离,从而导致优化失败。
在这里插入图片描述

2. 拓扑路径搜索

参考博客
最短的路径引导不一定是最优的引导路径,因为路径是低维信息不包含高阶信息(速度、加速度等),不能反映真实运动。仿照笔者整理的可变性路径利用拓扑等价轨迹获得多条轨迹再进一步优化剪枝。
该算法主要体现在topo_prm.cpp代码中,现在解析这部分代码。

2.1 主函数

/*function:拓扑路径搜索主函数param:- start 起点坐标- end 终点坐标- start_pts 不知道干什么- end_pts 同上- graph 节点图- raw_paths 搜索到的路径集合- filtered_paths 剪枝后的路径合集- select_paths  最后选择的比较短的几条路径
*/
void TopologyPRM::findTopoPaths(Eigen::Vector3d start, Eigen::Vector3d end,vector<Eigen::Vector3d> start_pts, vector<Eigen::Vector3d> end_pts,list<GraphNode::Ptr>& graph, vector<vector<Eigen::Vector3d>>& raw_paths,vector<vector<Eigen::Vector3d>>& filtered_paths,vector<vector<Eigen::Vector3d>>& select_paths) {ros::Time t1, t2;//用于计时每个阶段的时间:生成节点时间、路径搜索时间、路径最短时间、路径剪枝时间、选择路径时间double graph_time, search_time, short_time, prune_time, select_time;/* ---------- create the topo graph ---------- */t1 = ros::Time::now();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_t1 = ros::Time::now();//路径缩短优化shortcutPaths();short_time = (ros::Time::now() - t1).toSec();/* ---------- prune equivalent paths ---------- */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;
}

2.2 Algorithm 1: Topological Roadmap

在这里插入图片描述对应的函数是createGraph
在这里插入图片描述

/*function:根据起始点和终点的位置信息,采样地图节点(对应文章算法1 Topological Roadmap)param:- start 起点坐标- end 终点坐标
*/
list<GraphNode::Ptr> 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();//将起点和值哦观点设为守卫节点,并标定id号分别为0和1GraphNode::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); //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 *//* 找到前采样点的可视守卫点合集 */vector<GraphNode::Ptr> visib_guards = findVisibGuard(pt);if (visib_guards.size() == 0) {   //没有可视守卫点,将其设为守卫点GraphNode::Ptr guard = GraphNode::Ptr(new GraphNode(pt, GraphNode::Guard, ++node_id));graph_.push_back(guard);} else if (visib_guards.size() == 2) {  //如果有且只有两个可见guard,则要利用needConnection函数判断是否要添加新的connector。/* try adding new connection between two guard */// vector<pair<GraphNode::Ptr, GraphNode::Ptr>> sort_guards =// sortVisibGuard(visib_guards);bool need_connect = needConnection(visib_guards[0], visib_guards[1], pt);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 guardsvisib_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);
}

这个函数里提到一个概念叫做UVD(uniform visibility deformation)均匀可视变形,同样来自上文提到的整理的论文笔记中,其中不一样的点在于相比于右图的分均匀可视变形,可视变形的检测可以通过均匀采样一一可视检测完成,然后从两条可视变形的路径中挑选出最短的一条添加进节点图,这个算法的代码函数为sameTopoPath。论文中提到在概念上,UVD不太普遍,它是VD类型的子集的特征。实际上,它捕获的不同路径的类别比VD略多,但等价性检查的成本要低得多。
在这里插入图片描述

bool TopologyPRM::sameTopoPath(const vector<Eigen::Vector3d>& path1,const vector<Eigen::Vector3d>& path2, double thresh) {// 计算两条路径的长度double len1 = pathLength(path1);double len2 = pathLength(path2);double max_len = max(len1, len2);int pt_num = ceil(max_len / resolution_);// std::cout << "pt num: " << pt_num << std::endl;// 离散path的路径点vector<Eigen::Vector3d> pts1 = discretizePath(path1, pt_num);vector<Eigen::Vector3d> pts2 = discretizePath(path2, pt_num);Eigen::Vector3d pc;for (int i = 0; i < pt_num; ++i) {// 判断轨迹上是否有障碍物(两条轨迹均匀可视变形)if (!lineVisib(pts1[i], pts2[i], thresh, pc)) {return false;}}return true;
}

2.2 深度搜索

在获得节点图后,从起点到终点有好多个点,本文采用深度搜索找到所用节点最少的路径集合。

// search for useful path in the topo graph by DFS
// 通过DFS在节点图中搜索有用的路径,按节点数目对路径进行排序,选择节点数目较少的路径进行保留
vector<vector<Eigen::Vector3d>> TopologyPRM::searchPaths() {raw_paths_.clear();vector<GraphNode::Ptr> visited;     //标记节点是否被访问visited.push_back(graph_.front());  //存入起点depthFirstSearch(visited);  //进行DFS更新raw_paths向量// 路径排序int min_node_num = 100000, max_node_num = 1;vector<vector<int>> path_list(100);for (int i = 0; i < raw_paths_.size(); ++i) {if (int(raw_paths_[i].size()) > max_node_num) max_node_num = raw_paths_[i].size();if (int(raw_paths_[i].size()) < min_node_num) min_node_num = raw_paths_[i].size();path_list[int(raw_paths_[i].size())].push_back(i);}// 选择节点数较少的路径vector<vector<Eigen::Vector3d>> filter_raw_paths;for (int i = min_node_num; i <= max_node_num; ++i) {bool reach_max = false;for (int j = 0; j < path_list[i].size(); ++j) {filter_raw_paths.push_back(raw_paths_[path_list[i][j]]);if (filter_raw_paths.size() >= max_raw_path2_) {reach_max = true;break;}}if (reach_max) break;}std::cout << ", raw path num: " << raw_paths_.size() << ", " << filter_raw_paths.size();raw_paths_ = filter_raw_paths;return raw_paths_;
}void TopologyPRM::depthFirstSearch(vector<GraphNode::Ptr>& vis) {GraphNode::Ptr cur = vis.back();  //从已访问节点列表中获取最后一个节点作为当前节点for (int i = 0; i < cur->neighbors_.size(); ++i) {// 检查邻居点中是否有目标节点if (cur->neighbors_[i]->id_ == 1) {// 将当前路径添加到raw_pathsvector<Eigen::Vector3d> path;for (int j = 0; j < vis.size(); ++j) {path.push_back(vis[j]->pos_);}path.push_back(cur->neighbors_[i]->pos_);raw_paths_.push_back(path);if (raw_paths_.size() >= max_raw_path_) return;break;}}for (int i = 0; i < cur->neighbors_.size(); ++i) {// 跳过目标节点if (cur->neighbors_[i]->id_ == 1) continue;// 检查是否已访问过当前邻居节点  bool revisit = false;for (int j = 0; j < vis.size(); ++j) {if (cur->neighbors_[i]->id_ == vis[j]->id_) {revisit = true;break;}}if (revisit) continue;  //如果已访问过,则跳过该邻居节点// 将当前邻居节点添加到访问列表中,并递归搜索vis.push_back(cur->neighbors_[i]);depthFirstSearch(vis);if (raw_paths_.size() >= max_raw_path_) return;vis.pop_back(); //回溯,从访问列表中移除当前邻居节点}
}

2.3 路径缩短

将原路径离散化成多个点,然后从起点出发,遍历原路径上的离散点连成线,如果与障碍物碰撞,从碰撞处的障碍的ESDF梯度结合连线向外推出一定距离形成新路径的一个点,然后以这个新点做遍历直到达到目标点。这部分代码为函数shortcutPaths,可选择并行缩短多条路径。
在这里插入图片描述在这里插入图片描述

/*function:通过对路径进行优化,找到一条更短或更高效的路径,同时避免与障碍物或其他不可行区域发生碰撞(对应论文中的算法2)param:- path: 待优化的原始路径- path_id: 编号- iter_num:迭代次数
*/
void TopologyPRM::shortcutPath(vector<Eigen::Vector3d> path, int path_id, int iter_num) {vector<Eigen::Vector3d> short_path = path;vector<Eigen::Vector3d> last_path;for (int k = 0; k < iter_num; ++k) {last_path = short_path;//将路径稠密化vector<Eigen::Vector3d> dis_path = discretizePath(short_path);if (dis_path.size() < 2) {short_paths_[path_id] = dis_path;return;}/* visibility path shortening *///              障碍物id   梯度   方向  推力方向Eigen::Vector3d colli_pt, grad, dir, push_dir;double dist;short_path.clear();short_path.push_back(dis_path.front());for (int i = 1; i < dis_path.size(); ++i) {//利用lineVisib来衡量可见性,找到线上不可见的第一个点if (lineVisib(short_path.back(), dis_path[i], resolution_, colli_pt, path_id)) continue;//计算障碍点上的梯度edt_environment_->evaluateEDTWithGrad(colli_pt, -1, dist, grad);if (grad.norm() > 1e-3) {grad.normalize();//计算到第一个新点的方向dir = (dis_path[i] - short_path.back()).normalized();push_dir = grad - grad.dot(dir) * dir;  //推离方向push_dir.normalize();colli_pt = colli_pt + resolution_ * push_dir; //推离到新点}short_path.push_back(colli_pt); //添加点}short_path.push_back(dis_path.back());/* break if no shortcut */// 比较两个路径的长度,保留短的double len1 = pathLength(last_path);double len2 = pathLength(short_path);if (len2 > len1) {// ROS_WARN("pause shortcut, l1: %lf, l2: %lf, iter: %d", len1, len2, k +// 1);short_path = last_path;break;}}short_paths_[path_id] = short_path;
}//对通过DFS找到的原始路径进行shortcut处理,用于减少路径中的冗余节点,以得到更短或更高效的路径。
void TopologyPRM::shortcutPaths() {short_paths_.resize(raw_paths_.size());if (parallel_shortcut_) { //是否开启多线程并行处理每条路径vector<thread> short_threads;for (int i = 0; i < raw_paths_.size(); ++i) {short_threads.push_back(thread(&TopologyPRM::shortcutPath, this, raw_paths_[i], i, 1));}for (int i = 0; i < raw_paths_.size(); ++i) {short_threads[i].join();}} else {for (int i = 0; i < raw_paths_.size(); ++i) shortcutPath(raw_paths_[i], i);}
}

2.4 剪枝

/*function:将路径集中的其他路径与最短路径进行比较,产生一个长度比值,该比值小于阈值,将该路径放入新的路径集中保留,直到达到新的路径集中保留。
*/
vector<vector<Eigen::Vector3d>> TopologyPRM::selectShortPaths(vector<vector<Eigen::Vector3d>>& paths,int step) {/* ---------- only reserve top short path ---------- */vector<vector<Eigen::Vector3d>> short_paths;vector<Eigen::Vector3d> short_path;double min_len;for (int i = 0; i < reserve_num_ && paths.size() > 0; ++i) {int path_id = shortestPath(paths);if (i == 0) {short_paths.push_back(paths[path_id]);min_len = pathLength(paths[path_id]);paths.erase(paths.begin() + path_id);} else {//路径长度比较double rat = pathLength(paths[path_id]) / min_len;if (rat < ratio_to_short_) {short_paths.push_back(paths[path_id]);paths.erase(paths.begin() + path_id);} else {break;}}}std::cout << ", select path num: " << short_paths.size();/* ---------- merge with start and end segment ---------- */for (int i = 0; i < short_paths.size(); ++i) {short_paths[i].insert(short_paths[i].begin(), start_pts_.begin(), start_pts_.end());short_paths[i].insert(short_paths[i].end(), end_pts_.begin(), end_pts_.end());}for (int i = 0; i < short_paths.size(); ++i) {shortcutPath(short_paths[i], i, 5);short_paths[i] = short_paths_[i];}short_paths = pruneEquivalent(short_paths);return short_paths;
}

完整代码参考

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.mzph.cn/news/806605.shtml

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

未设置超时时间导致线程池资源耗尽,排查过程

错误分析&#xff1a; Scheduled进行定时任务的时候&#xff0c;spring会创建一个线程&#xff0c;然后用这个线程来执行任务&#xff0c;如果这个任务阻塞了&#xff0c;那么这个任务就会停滞&#xff0c;出现不执行的情况。而使用原生的方法进行http请求时&#xff0c;如果不…

应该如何进行POC测试?—【DBA从入门到实践】第三期

在数据库选型过程中&#xff0c;为确保能够灵活应对数据规模的不断扩大和处理需求的日益复杂化&#xff0c;企业和技术人员会借助POC测试来评估不同数据库系统的性能。在测试过程中&#xff0c;性能、并发处理能力、存储成本以及高可用性等核心要素通常会成为大家关注的焦点&am…

分析染色体级别的基因组装配揭示了六倍体栽培菊花的起源和进化-文献精读-7

Analyses of a chromosome-scale genome assembly reveal the origin and evolution of cultivated chrysanthemum 分析染色体级别的基因组装配揭示了栽培菊花的起源和进化 六倍体植物基因组的文献&#xff0c;各位同仁还有什么有特色的基因组评论区留言~ 摘要 菊花&#xf…

如何将PHP的Webman框架打包成二进制文件运行

看了看webman的官方文档&#xff0c;发现居然还能打包为二进制&#xff0c;这样太厉害了吧&#xff01; 先执行这个 composer require webman/console ^1.2.24 安装这个console的包&#xff0c;然后 执行 php webman build:bin 8.1 结果谁想到它报错提示&#xff1a; 好…

Lesson1--数据结构前言

1. 什么是数据结构&#xff1f; 2. 什么是算法&#xff1f; 3. 数据结构和算法的重要性 4. 如何学好数据结构和算法 5. 数据结构和算法书籍及资料推荐 1. 什么是数据结构&#xff1f; 数据结构(Data Structure) 是计算机存储、组织数据的方式&#xff0c;指相互之间存在一…

机器学习和深度学习-- 李宏毅(笔记与个人理解)Day8

Day 8 classification &#xff1a;Probabilistic Generative Model 今天上了一整天的课&#xff0c; 本来实在是更新不动了&#xff0c;但是看到《剑来》更新了&#xff0c;想一想这本书里面一直强调的成功的feature – 心性&#xff0c;嗯心性坚毅就好&#xff01;主人公陈平…

Unity 遮罩

编辑器版本 2017.2.3f1 学习Unity的三张遮罩方式 1. Mask 遮罩方式 首先&#xff0c;在界面上创建2个Image&#xff0c;一个命名Img_Mask,大小设置 400* 400&#xff0c; 一个命名Img_Show,大小设置500*500。 然后&#xff0c;给 Img_Mask添加Mask,选择Img_Mask,点击Add Com…

docker 创建容器过程

结合下图&#xff0c;本文讨论docker 创建容器过程&#xff1a; START└── [用户通过Docker Client发出指令]└── (1) docker run 或 docker create 命令├── (2) Docker Client与Docker Daemon建立通信连接└── (3) Docker Daemon接收到创建容器请求├── (4) 检查…

Python --- Python + Vs code的安装与使用(windows平台)

Python Vs code的安装与使用 今天是我第一次开始尝试用Python&#xff0c;然后我想借此机会记录一下整个安装过程和上手过程。之前一直都是用的matlab&#xff0c;这个东西不仅大而且收费&#xff0c;但不可否认的是。matlab的很多东西都做的比较好&#xff0c;但我一直用的都…

【Linux的进程篇章 - 进程终止和进程等待的理解】

Linux学习笔记---008 Linux之fork函数、进程终止和等待的理解1、fork函数1.1、什么是fork?1.2、fork的功能介绍1.3、fork函数返回值的理解1.4、fork函数的总结 2、进程的终止2.1、终止是在做什么&#xff1f;2.2、进程终止的3种情况 3、进程的终止3.1、进程终止的三种情况3.2、…

1.8.4 卷积神经网络近年来在结构设计上的主要发展和变迁——Inception-v2 和Inception-v3

1.8.4 卷积神经网络近年来在结构设计上的主要发展和变迁——Inception-v2 和Inception-v3 前情回顾&#xff1a; 1.8.1 卷积神经网络近年来在结构设计上的主要发展和变迁——AlexNet 1.8.2 卷积神经网络近年来在结构设计上的主要发展和变迁——VGGNet 1.8.3 卷积神经网络近年来…

阿里Canal使用

Canal 是阿里巴巴开源的一款基于 MySQL 数据库增量日志解析&#xff0c;提供实时的数据订阅和消费服务的工具。它可以用来读取 MySQL 的 binlog 日志并转换成 JSON 格式的事件消息&#xff0c;然后将这些消息发布到下游的消息中间件&#xff0c;比如 RabbitMQ&#xff0c;以实现…

MySQL innoDB存储引擎多事务场景下的事务执行情况

一、背景 在日常开发中&#xff0c;对不同事务之间的隔离情况等理解如果不够清晰&#xff0c;很容易导致代码的效果和预期不符。因而在这对一些存在疑问的场景进行模拟。 下面的例子全部基于innoDB存储引擎。 二、场景&#xff1a; 2.1、两个事务修改同一行记录 正常来说&…

自动化测试框架-senlenium(2)

目录 1.前言 2.鼠标点击 2.1click点击对象 2.2senk_keys在对象上模拟键盘输入 2.3清除对象输入的文本内容 2.4submit提交 2.5 text用于获取文本信息 ​编辑3.获取信息 3.1获取title 3.2获取url 1.前言 前面我们讲了如何定位元素,那么我们把元素定位到了以后,又如何…

【力扣】104. 二叉树的最大深度、111. 二叉树的最小深度

104. 二叉树的最大深度 题目描述 给定一个二叉树 root &#xff0c;返回其最大深度。 二叉树的 最大深度 是指从根节点到最远叶子节点的最长路径上的节点数。 示例 1&#xff1a; 输入&#xff1a;root [3,9,20,null,null,15,7] 输出&#xff1a;3 示例 2&#xff1a; 输…

ENSP防火墙配置策略路由及ip-link探测

拓扑 配置目标 1.A区域走ISP1&#xff0c;B区域走ISP2 2. isp线路故障时及时切换到另一条线路 配置接口及安全区域 配置安全策略 配置nat 配置默认路由 配置ip-link 配置策略路由 cl-1 cl-2 验证配置成功 策略路由 A走ISP1 B走ISP2 验证线路故障 isp1 in g0/0/0 shoutdow…

Qt——示波器/图表 QCustomPlot

一、介绍 QCustomPlot是一个用于绘图和数据可视化的Qt C小部件。它没有进一步的依赖关系&#xff0c;提供友好的文档帮助。这个绘图库专注于制作好看的&#xff0c;出版质量的2D绘图&#xff0c;图形和图表&#xff0c;以及为实时可视化应用程序提供高性能。QCustomPlot可以导出…

HWOD:走方格的方案数

一、自己的解题思路 1、(0,m)和(n,0) (0,m)表示处在棋盘的左边线&#xff0c;此刻能回到原点的路线只有一个&#xff0c;就是一路向上 (n,0)表示处在棋盘的上边线&#xff0c;此刻能回到原点的路线只有一个&#xff0c;就是一路向左 2、(1,1) (1,1)表示只有一个方格&#…

02 Git 之IDEA 集成使用 GitHub(Git同时管理本地仓库和远程仓库)

2 .IDEA 集成使用 GitHub&#xff08;Git同时管理本地仓库和远程仓库&#xff09; 首先在 IDEA 的设置中绑定 GitHub 的账号 先创建一个 test1.txt 文件&#xff0c;内容为 aaa. 最上一栏 VCS&#xff0c; SHARE ON GitHub&#xff0c;然后选择要发送到远程仓库的文件即可。…

Vue实现防篡改水印的效果。删除元素无效!更改元素属性无效!支持图片、元素、视频等等。

1、演示 2、水印的目的 版权保护&#xff1a;水印可以在图片、文档或视频中嵌入作者、品牌或版权所有者的信息&#xff0c;以防止未经授权的复制、传播或使用。当其他人使用带有水印的内容时&#xff0c;可以追溯到原始作者或版权所有者&#xff0c;从而加强版权保护。 身份识…