轨迹优化 | 基于贝塞尔曲线的无约束路径平滑与粗轨迹生成(附ROS C++/Python仿真)

目录

  • 0 专栏介绍
  • 1 从路径到轨迹
  • 2 基于贝塞尔曲线的粗轨迹生成
    • 2.1 路径关键点提取
    • 2.2 路径点航向角计算
    • 2.3 贝塞尔曲线轨迹生成
  • 3 算法仿真
    • 3.1 ROS C++仿真
    • 3.2 Python仿真

0 专栏介绍

🔥课设、毕设、创新竞赛必备!🔥本专栏涉及更高阶的运动规划算法轨迹优化实战,包括:曲线生成、碰撞检测、安全走廊、优化建模(QP、SQP、NMPC、iLQR等)、轨迹优化(梯度法、曲线法等),每个算法都包含代码实现加深理解

🚀详情:运动规划实战进阶:轨迹优化篇


1 从路径到轨迹

路径规划和轨迹生成是自主导航和机器人控制中的两个关键步骤,它们虽然相关,但有着不同的目的和功能。

路径规划的目的是找到从起点到终点的一条可行路径,通常是在已知环境中进行。路径规划算法考虑的是全局的几何路径,不关心时间和动态特性,其输出通常是一个离散的路径点集合,这些点表示机器人在空间中的位置 { x , y , z } \{x,y,z\} {x,y,z}

轨迹生成是在路径规划的基础上,为机器人生成一条平滑、可执行的轨迹。轨迹生成不仅考虑空间上的位置,还包括时间、速度、加速度等动态特性。轨迹生成的目的是确保机器人沿着路径点运动时,速度和加速度都是可控和安全的。轨迹的相关参数包括

{ x , y , z , θ , t , v , a , j e r k , . . . } \{x,y,z,\theta ,t,v,a,jerk, ...\} {x,y,z,θ,t,v,a,jerk,...}

在优化问题中,使用轨迹进行优化比单纯用路径进行优化有诸多优势。具体而言,轨迹同时包含静态和动态的丰富信息,且通常连续可微,因此可以方便地对轨迹设计目标函数,添加速度、加速度等动态约束,进一步生成符合物理特性的轨迹。

本节介绍的基于贝塞尔曲线的粗轨迹生成模块主要用于将上游规划的离散路径点转为连续的多项式轨迹,为进一步的轨迹优化做准备。

2 基于贝塞尔曲线的粗轨迹生成

2.1 路径关键点提取

本节采用路径处理 | 关键点提取之Douglas–Peucker算法(附ROS C++/Python实现)的道格拉斯-普克算法(Douglas–Peucker)提取路径关键点,在保留路径关键特征和形状的基础上滤除噪点,使生成的轨迹更稳定、更平滑

在这里插入图片描述

剪枝前(红色点表示路径点)

在这里插入图片描述

剪枝后(红色点表示路径点)

2.2 路径点航向角计算

经过2.1节的路径预处理,得到二维离散路点 { x i , y i } ( i = 1 , . . . , N ) \{x_i,y_i\}(i=1,...,N) {xi,yi}(i=1,...,N)。默认状态下,除了用户给定的起始点和终点外,其余的路点来自路径规划算法的结果,并没有朝向角的定义,而路点的朝向对于机器人运动而言至关重要。

本节通过简单的几何学原理赋予路点方向。具体地,根据三点共圆的性质,可以计算每三个点 p 1 \boldsymbol{p}_1 p1 p 2 \boldsymbol{p}_2 p2 p 3 \boldsymbol{p}_3 p3所在圆的圆心坐标 c \boldsymbol{c} c

在这里插入图片描述

取向量 p 2 c \boldsymbol{p_2c} p2c的法向量即为路点 p 2 \boldsymbol{p}_2 p2的朝向

在这里插入图片描述

由于首末路点的朝向给定,所以通过该算法可以确定路径上每个位置的方向

2.3 贝塞尔曲线轨迹生成

贝塞尔曲线是一种数学曲线,由法国数学家皮埃尔·贝塞尔于1962年引入。它使用一组控制点来定义曲线的形状,这些控制点的位置和数量决定了曲线的特征。贝塞尔曲线因为其凸包性、端点性等优良性质被广泛应用于机器人运动规划中,其具体的原理请看曲线生成 | 图解贝塞尔曲线生成原理(附ROS C++/Python/Matlab仿真)

在贝塞尔曲线中,通过相邻两个路径点及其朝向,可以启发式地定义两个控制点。在四个点的约束下,本节选用三次贝塞尔曲线进行轨迹插值

p = [ ( p 3 − p 0 ) − 3 ( p 2 − p 1 ) ] t 3 + [ 3 ( p 2 − p 1 ) − 3 ( p 1 − p 0 ) ] t 2 + 3 ( p 1 − p 0 ) t + p 0 \begin{aligned}\boldsymbol{p}&=[(\boldsymbol{p_3}-\boldsymbol{p_0})-3(\boldsymbol{p_2}-\boldsymbol{p_1})]t^3 \\ &+[3(\boldsymbol{p_2}-\boldsymbol{p_1})-3(\boldsymbol{p_1}-\boldsymbol{p_0})]t^2 \\ &+3(\boldsymbol{p_1}-\boldsymbol{p_0})t \\&+\boldsymbol{p_0}\end{aligned} p=[(p3p0)3(p2p1)]t3+[3(p2p1)3(p1p0)]t2+3(p1p0)t+p0

在这里插入图片描述

3 算法仿真

3.1 ROS C++仿真

核心代码如下所示

for (size_t i = 1; i <= waypoints_.size(); i++)
{if ((!std::isinf(prelast_dir.x())) && (!std::isinf(prelast_dir.y()))){...// Interpolate poses between prelast and lastauto prelast_pt = Point3d(waypoints_[i - 2].x(), waypoints_[i - 2].y(), prelast_dir.angle());auto last_pt = Point3d(waypoints_[i - 1].x(), waypoints_[i - 1].y(), last_dir.angle());auto interp_pts = bezier_gen_->generation(prelast_pt, last_pt);// Assign orientations to interpolated pointstrajectory_.position.emplace_back(prelast_pt);if (interp_pts.size() > 0){for (size_t j = 1; j < interp_pts.size() - 1; j++){auto prev_interp_vec = Vec2d(interp_pts[j - 1].x(), interp_pts[j - 1].y());auto curr_interp_vec = Vec2d(interp_pts[j].x(), interp_pts[j].y());auto next_interp_vec = Vec2d(interp_pts[j + 1].x(), interp_pts[j + 1].y());auto tangent_dir = rmp::common::math::tangentDir(prev_interp_vec, curr_interp_vec, next_interp_vec, false);auto dir = tangent_dir.innerProd(curr_interp_vec - prev_interp_vec) >= 0 ? tangent_dir : -tangent_dir;trajectory_.position.emplace_back(interp_pts[j].x(), interp_pts[j].y(), dir.angle());}}trajectory_.position.emplace_back(last_pt);prelast_dir = last_dir;}

在这里插入图片描述
在这里插入图片描述

3.2 Python仿真

核心代码如下所示

for i in range(1, len(waypoints) + 1):if prelast_dir is not None:last_dir = Vec2d()prelast = Vec2d(waypoints[i - 2].x(), waypoints[i - 2].y())last = Vec2d(waypoints[i - 1].x(), waypoints[i - 1].y())# Compute orientation of lastif i < len(waypoints):current = Vec2d(waypoints[i].x(), waypoints[i].y())tangent_dir = MathHelper.tangentDir(prelast, last, current)last_dir = tangent_dir if tangent_dir.innerProduct(current - last) >= 0 else -tangent_dirlast_dir.normalize()elif self.keep_goal_orientation:last_dir = goal_direlse:last_dir = last - prelastlast_dir.normalize()last_angle = last_dir.angle()# Interpolate poses between prelast and lastprelast_pt, last_pt = waypoints[i - 2], waypoints[i - 1]prelast_pt.setTheta(prelast_dir.angle())last_pt.setTheta(last_dir.angle())interp_pts, _ = self.traj_gen.generation(prelast_pt, last_pt)interp_cnt = len(interp_pts)self.trajectory += interp_pts# Assign orientations to interpolated pointstraj_size = len(self.trajectory)for j in range(traj_size - 1 - interp_cnt, traj_size - 1):tangent_dir = MathHelper.tangentDir(Vec2d(self.trajectory[j - 1].x(), self.trajectory[j - 1].y()),Vec2d(self.trajectory[j].x(), self.trajectory[j].y()),Vec2d(self.trajectory[j + 1].x(), self.trajectory[j + 1].y()))self.trajectory[j].setTheta(tangent_dir.angle())prelast_dir = last_dir

在这里插入图片描述

可视化轨迹点和关键点朝向

在这里插入图片描述

完整工程代码请联系下方博主名片获取


🔥 更多精彩专栏

  • 《ROS从入门到精通》
  • 《Pytorch深度学习实战》
  • 《机器学习强基计划》
  • 《运动规划实战精讲》

👇源码获取 · 技术交流 · 抱团学习 · 咨询分享 请联系👇

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

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

相关文章

理解STC15F2K60S2单片机的最小电路

一、STC15F2K60S2与51单片机的区别 STC15F2K60S2和51单片机虽然都基于8051内核&#xff0c;但在多个方面存在显著区别&#xff1a; 1. CPU性能&#xff1a; - STC15F2K60S2&#xff1a;采用增强型8051 CPU&#xff0c;1T单时钟/机器周期&#xff0c;速度比普通8051快8-12倍…

微信小程序获取当前页面路径,登录成功后重定向回原页面

&#x1f935; 作者&#xff1a;coderYYY &#x1f9d1; 个人简介&#xff1a;前端程序媛&#xff0c;目前主攻web前端&#xff0c;后端辅助&#xff0c;其他技术知识也会偶尔分享&#x1f340;欢迎和我一起交流&#xff01;&#x1f680;&#xff08;评论和私信一般会回&#…

Linux学习指南与资料分享

Linux学习资料 Linux学习资料 Linux学习资料 基础入门 了解 Linux 基础概念&#xff1a; Linux 是开源类 Unix 操作系统&#xff0c;由内核、Shell 和应用程序组成。学习时要了解其开源、稳定、安全等特性&#xff0c;以及多用户、多任务的特点。 选择并安装 Linux 发行版…

VSCode 搜索 搜不到

VSCode 搜索 搜不到 今天打开一个新的工作目录之后 ctrl P 搜文件 搜不到 经观察后发现 当我搜索时候&#xff0c; 右侧搜索按钮有一个时钟标识&#xff0c;疑似 搜索的范围 是最近打开内容。 经过和全局搜索的编辑器对比设置后发现&#xff0c;把设置中 下图中 选项去掉勾选…

软件测试 —— Selenium常用函数

软件测试 —— Selenium常用函数 操作测试对象点击/提交对象 click()模拟按键输入 send_keys("")清除文本内容 clear() 模拟用户键盘行为 Keys包示例用法 获取文本信息 textget_attribute("属性名称") 获取当前页面标题 title获取当前页面的 url current_u…

【9.1】Golang后端开发系列--Gin快速入门指南

文章目录 一、引言 &#x1f31f;二、Gin 框架概述 &#x1f4d6;&#xff08;一&#xff09;什么是 Gin&#xff08;二&#xff09;为什么选择 Gin 三、安装 Gin 框架 &#x1f4e6;&#xff08;一&#xff09;安装 Go 语言环境&#xff08;二&#xff09;使用 Go Modules 安装…

Vue 学习之旅:核心技术学习总结与实战案例分享(vue指令下+计算属性+侦听器)

Vue 学习之旅&#xff1a;核心技术学习总结与实战案例分享 文章目录 Vue 学习之旅&#xff1a;核心技术学习总结与实战案例分享一、指令补充&#xff08;一&#xff09;指令修饰符&#xff08;二&#xff09;v-bind 对样式操作的增强&#xff08;三&#xff09;v-model 应用于其…

OpenCV相机标定与3D重建(55)通用解决 PnP 问题函数solvePnPGeneric()的使用

操作系统&#xff1a;ubuntu22.04 OpenCV版本&#xff1a;OpenCV4.9 IDE:Visual Studio Code 编程语言&#xff1a;C11 算法描述 根据3D-2D点对应关系找到物体的姿态。 cv::solvePnPGeneric 是 OpenCV 中一个更为通用的函数&#xff0c;用于解决 PnP 问题。它能够返回多个可能…

UE5 打包项目

UE5 打包项目 flyfish 通过 “文件”->“打开项目”&#xff0c;然后在弹出的对话框中选择项目文件&#xff08;通常是以.uproject为后缀的文件&#xff09; 选择目标平台&#xff1a; 在 UE5 主界面中&#xff0c;找到 “平台”&#xff08;Platforms&#xff09;。根据…

1. Doris分布式环境搭建

一. 环境准备 本次测试集群采用3台机器hadoop1、hadoop2、hadoop3, Frontend和Backend部署在同一台机器上&#xff0c;Frontend部署3台组成高可用&#xff0c;Backend部署3个节点&#xff0c;组成3副本存储。 主机IP操作系统FrontendBackendhadoop1192.168.47.128Centos7Foll…

win10电脑 定时关机

win10电脑 定时关机 https://weibo.com/ttarticle/p/show?id2309405110707766296723 二、使用任务计划程序设置定时关机打开任务计划程序&#xff1a; 按下“Win S”组合键&#xff0c;打开搜索框。 在搜索框中输入“任务计划程序”&#xff0c;然后点击搜索结果中的“任务…

Markdown中甘特图的使用

Markdown中甘特图的使用 1. 前言2. 语法详解2.1 甘特图语法 3. 使用场景及实例4. 小结5. 其他文章快来试试吧&#x1f58a;️ Markdown中甘特图的使用 &#x1f448;点击这里也可查看 1. 前言 Markdown 的原生语法不支持绘制图形&#xff0c;但通过扩展模块&#xff0c;我们可…

python bs4 selenium 查找a href=javascript:();的实际点击事件和url

在使用 BeautifulSoup 和 Selenium 时&#xff0c;处理 href"javascript:;" 的链接需要一些额外的步骤&#xff0c;因为这些链接不直接指向一个 URL&#xff0c;而是通过 JavaScript 代码来执行某些操作。这可能包括导航到另一个页面、触发模态窗口、显示/隐藏内容等…

day07_Spark SQL

文章目录 day07_Spark SQL课程笔记一、今日课程内容二、Spark SQL函数定义&#xff08;掌握&#xff09;1、窗口函数2、自定义函数背景2.1 回顾函数分类标准:SQL最开始是_内置函数&自定义函数_两种 2.2 自定义函数背景 3、Spark原生自定义UDF函数3.1 自定义函数流程&#x…

Laravel 中 Cache::remember 的基本用途

在 Laravel 中&#xff0c;Cache::remember 方法用于缓存数据&#xff0c;以提高应用程序的性能。当需要从数据库或其他较慢的数据源中检索数据时&#xff0c;可以使用 Cache::remember 来检查请求的数据是否已经被缓存。如果数据已缓存&#xff0c;则直接从缓存中读取&#xf…

如何解决HTML和CSS相关的问题,什么情况下会导致元素被遮挡?

在开发过程中&#xff0c;HTML 和 CSS 中的元素遮挡问题通常是由于布局、定位、层级等因素导致的。在使用 Vue.js 时&#xff0c;这些问题依然常见&#xff0c;尤其是涉及到动态渲染、条件渲染和组件嵌套的场景。以下是一些常见的导致元素被遮挡的原因&#xff0c;并通过 Vue.j…

Hadoop3.x 万字解析,从入门到剖析源码

&#x1f496; 欢迎来到我的博客&#xff01; 非常高兴能在这里与您相遇。在这里&#xff0c;您不仅能获得有趣的技术分享&#xff0c;还能感受到轻松愉快的氛围。无论您是编程新手&#xff0c;还是资深开发者&#xff0c;都能在这里找到属于您的知识宝藏&#xff0c;学习和成长…

Java 实现 Elasticsearch 查询当前索引全部数据

Java 实现 Elasticsearch 查询当前索引全部数据 需求背景通常情况Java 实现查询 Elasticsearch 全部数据写在最后 需求背景 通常情况下&#xff0c;Elasticsearch 为了提高查询效率&#xff0c;对于不指定分页查询条数的查询语句&#xff0c;默认会返回10条数据。那么这就会有…

Elasticsearch ES|QL 地理空间索引加入纽约犯罪地图

可以根据地理空间数据连接两个索引。在本教程中&#xff0c;我将向你展示如何通过混合邻里多边形和 GPS 犯罪事件坐标来创建纽约市的犯罪地图。 安装 如果你还没有安装好自己的 Elasticsearch 及 Kibana 的话&#xff0c;请参考如下的链接来进行安装。 如何在 Linux&#xff0…

C#学习笔记 --- 简单应用

1.operator 运算符重载&#xff1a;使自定义类可以当做操作数一样进行使用。规则自己定。 2.partial 分部类&#xff1a; 同名方法写在不同位置&#xff0c;可以当成一个类使用。 3.索引器&#xff1a;使自定义类可以像数组一样通过索引值 访问到对应的数据。 4.params 数…