• 关节空间 VS 操作空间

  关节空间与操作空间轨迹规划流程图如下(上标$i$和$f$分别代表起始位置initial和目标位置final):

  在关节空间内进行轨迹规划有如下优点:

  1. 在线运算量更小,即无需进行机器人的逆解或正解解算
  2. 不受机器人奇异构型影响
  3. 可以根据机器人或驱动器手册直接确定最大速度或力矩

其缺点是对应操作空间的轨迹无法预测,增加了机械臂与环境碰撞的可能。例如,考虑下面的二连杆机构,关节运动的限制为:$0^{\circ} \le \theta_1 \le 180^{\circ}$,$0^{\circ} \le \theta_2 \le 150^{\circ}$

  下图中,左侧为关节空间内规划的线性运动轨迹,而其对应在操作空间的轨迹却是弧线。机构末端的可达空间在图中由灰色背景表示,其大小和形状受关节运动范围的影响。

  下图在操作空间中规划了一条直线轨迹,其对应的关节空间轨迹为一弧线,且在运动过程中超出了关节值限制。操作空间内进行轨迹规划优点是直观,缺点是计算量大(需要计算逆解),会遇到奇异性问题以及关节运动超限等。

  到底是选择在关节空间还是操作空间内进行轨迹规划,取决于任务需要。需要考虑避障或必须沿特定轨迹运动时选择操作空间轨迹规划,只需考虑速度、力矩、关节范围等运动约束时选择关节空间轨迹规划(The joint space scheme is appropriate to achieve fast motions in a free space)。

  • 梯形速度曲线

  运动控制系统中常用的梯形速度曲线如下图所示,会出现加速度不连续的情形(从$k_{aj}$到0的跳变),这样可能会导致机械系统出现冲击或不可预料的振动,不过由于机械系统存在一定的弹性并不是绝对刚体,这种加速度不连续造成的冲击会被机械机构滤除或减轻。而对于高速重载的机器人来说,这种加速度不连续造成的影响就不能忽略了。可以参考知乎上这个问题:多轴插补为什么普遍使用梯形速度曲线?

  •  S型速度曲线

  为了使加速度连续,可对梯形速度规划中的加速度曲线进行修改,使加速度曲线变为连续的二次曲线(a)或者梯形曲线(b),如下图所示。其中,$\tau'$为加速段时间,$\lambda_jk_{vj}$为第$j$个关节的最大运动速度

  下面考虑a方法(Linear Trajectory with Polynomial Blends),关节$j$的运动边界条件如下,即关节$j$初始时刻位置为$q_j^i$,初始速度加速度为0,$\tau'$时刻加速到最大速度$\lambda_ik_{vj}sign(D_i)$,$k_{vj}$为理论上关节$j$允许的最大速度,$\lambda_j$为一比例系数($0 \le \lambda_j \le 1$),$D_j$为从起始位置到目标位置的位移,它是一个有正负的数值。

  根据边界条件加速度二次曲线表达式为:$k(t-\tau')t$,对其进行积分,可得$\dot{q_j}(t)=\frac{1}{6}k(2t-3\tau')t^2+C$,根据速度边界条件可知$C=0$,$k=\frac{-6}{\tau'^3}\lambda_jk_{vj}$。于是推算出加速度、速度、位置的表达式分别为:$$\begin{cases}& q_j(t)=q_j^i-\frac{1}{\tau'^3}\lambda_jk_{vj}sign(D_j)(\frac{1}{2}t-\tau')t^3\\&\dot{q_j}(t)=-\frac{1}{\tau'^3}\lambda_jk_{vj}sign(D_j)(2t-3\tau')t^2\\&\ddot{q_j}(t)=-\frac{6}{\tau'^3}\lambda_jk_{vj}sign(D_j)(t-\tau')t  \end{cases}$$

  加速度在$t=\tau'/2$时最大,其幅值为$\left |\ddot{q}_{jmax} \right |=\frac{3}{2}\frac{\lambda_jk_{vj}}{\tau'}=\upsilon_j k_{aj}$,则有:$$\tau'=\frac{3}{2}\frac{\lambda_jk_{vj}}{\upsilon_j k_{aj}}$$

  根据上式和$q_j(t)$的表达式,可以计算出加速阶段的位移为:$$|q_j^i-q_j(\tau')|=\frac{3}{4}\frac{(\lambda_jk_{vj})^2}{\upsilon_j k_{aj}}$$

  速度曲线与时间轴围成的面积为$|D_j|$,根据计算可以得到关系式:$$t'_f=\tau'+\frac{|D_j|}{\lambda_jk_{vj}}$$

  在加速度为0的阶段(最大速度阶段,$\tau' \le t \le \tau'+h'$),关节速度表达式为:$$q_i(t)=q_j(\tau')+(t-\tau')\lambda_jk_{vj}sign(D_j)$$

  减速阶段与加速阶段对称($t'_f=2\tau'+h'$),减速阶段在时间段$\tau'+h' \le t \le t'_f$上的轨迹为:$$\begin{cases}&q_j(t)=q_j^f+\frac{1}{2}[\frac{1}{\tau'^3}(t-3\tau'-h')(t-\tau'-h')^3+(2t-3\tau'-2h')]\lambda_jk_{vj}sign(D_j) \\ &\dot{q_j}(t)=[\frac{1}{\tau'^3}(2t-5\tau'-2h')(t-\tau'-h')^2+1]\lambda_jk_{vj}sign(D_j)  \\  &\ddot{q_j}(t)= \frac{6}{\tau'^3}(t-2\tau'-h')(t-\tau'-h')\lambda_jk_{vj}sign(D_j)\end{cases}$$

  如果目标点距离初始位置过近,可能达不到最大速度和加速度就要开始减速,考虑以最大速度做匀速直线运动阶段的时间为0这种临界状态(The minimum time $t_f$ is obtained when the parameters $\lambda_j$ and $\upsilon_j$ are the largest),为了能以最大速度运动,位移$|D_j|$必须满足如下条件:$$|D_j| > \frac{3}{2}\frac{k_{vj}^2}{k_{aj}}$$  如果该条件不能满足,则最大速度值应为:$$k'_{vj}=\sqrt{\frac{2}{3}|D_j|k_{aj}}$$  前面的计算都只考虑单轴运动的情况,当需要多轴同步时,要考虑运动时间最长的轴(与每个轴的最大速度、运动位移等因素有关),将该时间作为同步运动的时间。在确定了同步时间之后,需要重新计算速度曲线的最大速度(运动快的轴要降低最大速度等待慢的轴),使得各轴在同一时刻到达设定的目标位置。

  参考《Modeling Identification and Control of Robots》的第 13.3.4节 Continuous acceleration profile with constant velocity phase 以及 libfranka MotionGenerator,修改关节空间轨迹规划代码,并在while循环中进行轨迹生成的模拟。

  traj.h

  1. #pragma once
  2.  
  3. #include <array>
  4. #include <Eigen/Core>
  5.  
  6. struct RobotState
  7. {
  8. std::array<double, > q_d{};
  9. };
  10.  
  11. class TrajectoryGenerator
  12. {
  13.  
  14. public:
  15.  
  16. // Creates a new TrajectoryGenerator instance for a target q.
  17. // @param[in] speed_factor: General speed factor in range [0, 1].
  18. // @param[in] q_goal: Target joint positions.
  19. TrajectoryGenerator(double speed_factor, const std::array<double, > q_goal);
  20.  
  21. // Calculate joint positions for use inside a control loop.
  22. bool operator()(const RobotState& robot_state, double time);
  23.  
  24. private:
  25. using Vector7d = Eigen::Matrix<double, , , Eigen::ColMajor>;
  26.  
  27. using Vector7i = Eigen::Matrix<int, , , Eigen::ColMajor>;
  28.  
  29. bool calculateDesiredValues(double t, Vector7d* delta_q_d); // generate joint trajectory
  30.  
  31. void calculateSynchronizedValues();
  32.  
  33. static constexpr double DeltaQMotionFinished = 1e-;
  34.  
  35. const Vector7d q_goal_;
  36.  
  37. Vector7d q_start_; // initial joint position
  38. Vector7d delta_q_; // the delta angle between start and goal
  39.  
  40. Vector7d dq_max_sync_;
  41. Vector7d t_1_sync_;
  42. Vector7d t_2_sync_;
  43. Vector7d t_f_sync_;
  44. Vector7d q_1_; // q_1_ = q(\tau) - q_start_
  45.  
  46. double time_ = 0.0;
  47.  
  48. Vector7d dq_max_ = (Vector7d() << 2.0, 2.0, 2.0, 2.0, 2.5, 2.5, 2.5).finished();
  49.  
  50. Vector7d ddq_max_ = (Vector7d() << , , , , , , ).finished();
  51.  
  52. Vector7d dq;
  53. };

  traj.cpp

  1. #include "traj.h"
  2. #include <algorithm>
  3. #include <array>
  4. #include <cmath>
  5.  
  6. TrajectoryGenerator::TrajectoryGenerator(double speed_factor, const std::array<double, > q_goal)
  7. : q_goal_(q_goal.data())
  8. {
  9. dq_max_ *= speed_factor;
  10. ddq_max_ *= speed_factor;
  11. dq_max_sync_.setZero();
  12. q_start_.setZero();
  13. delta_q_.setZero();
  14. t_1_sync_.setZero();
  15. t_2_sync_.setZero();
  16. t_f_sync_.setZero();
  17. q_1_.setZero();
  18. }
  19.  
  20. bool TrajectoryGenerator::calculateDesiredValues(double t, Vector7d* delta_q_d)
  21. {
  22. Vector7i sign_delta_q;
  23. sign_delta_q << delta_q_.cwiseSign().cast<int>(); // sign(D_j)
  24. Vector7d t_d = t_2_sync_ - t_1_sync_; // h'
  25. std::array<bool, > joint_motion_finished{}; // motion falgs
  26.  
  27. for (size_t i = ; i < ; i++) // calculate joint positions
  28. {
  29. if (std::abs(delta_q_[i]) < DeltaQMotionFinished){ // target approaches the goal
  30. (*delta_q_d)[i] = ;
  31. joint_motion_finished[i] = true;}
  32. else {
  33. if (t < t_1_sync_[i]) {
  34. (*delta_q_d)[i] = -1.0 / std::pow(t_1_sync_[i], 3.0) * dq_max_sync_[i] * sign_delta_q[i] * (0.5 * t - t_1_sync_[i]) * std::pow(t, 3.0);
  35. dq[i] = -1.0 / std::pow(t_1_sync_[i], 3.0) * dq_max_sync_[i] * sign_delta_q[i] * (2.0 * t - * t_1_sync_[i]) * std::pow(t, 2.0);
  36. }
  37. else if (t >= t_1_sync_[i] && t < t_2_sync_[i]) {
  38. (*delta_q_d)[i] = q_1_[i] + (t - t_1_sync_[i]) * dq_max_sync_[i] * sign_delta_q[i];
  39. dq[i] = dq_max_sync_[i];
  40. }
  41. else if (t >= t_2_sync_[i] && t < t_f_sync_[i]) {
  42. (*delta_q_d)[i] = delta_q_[i] + 0.5 *(1.0 / std::pow(t_1_sync_[i], 3.0) *(t - 3.0 * t_1_sync_[i] - t_d[i]) *std::pow((t - t_1_sync_[i] - t_d[i]), 3.0) + (2.0 * t - 3.0 * t_1_sync_[i] - 2.0 * t_d[i])) *dq_max_sync_[i] * sign_delta_q[i];
  43. dq[i] = (1.0 / std::pow(t_1_sync_[i], 3.0) *( * t - 5.0 * t_1_sync_[i] - * t_d[i])*std::pow((t - t_1_sync_[i] - t_d[i]), 2.0) + ) * dq_max_sync_[i] * sign_delta_q[i];
  44. }
  45. else {
  46. (*delta_q_d)[i] = delta_q_[i]; // reach the goal
  47. joint_motion_finished[i] = true;}
  48. }
  49. }
  50.  
  51. return std::all_of(joint_motion_finished.cbegin(), joint_motion_finished.cend(),[](bool x) { return x; });
  52. }
  53.  
  54. void TrajectoryGenerator::calculateSynchronizedValues()
  55. {
  56. Vector7d dq_max_reach(dq_max_);
  57. Vector7d t_f = Vector7d::Zero();
  58. Vector7d t_1 = Vector7d::Zero();
  59. Vector7i sign_delta_q;
  60. sign_delta_q << delta_q_.cwiseSign().cast<int>();
  61.  
  62. // only consider single axis
  63. for (size_t i = ; i < ; i++) {
  64. if (std::abs(delta_q_[i]) > DeltaQMotionFinished) {
  65. if ( std::abs(delta_q_[i]) < 3.0 / 2.0 * std::pow(dq_max_[i], 2.0) / ddq_max_[i] ) { // the goal not far enough from start position
  66. dq_max_reach[i] = std::sqrt( 2.0 / 3.0 * delta_q_[i] * sign_delta_q[i] * ddq_max_[i] ); // recalculate the maximum velocity
  67. }
  68. t_1[i] = 1.5 * dq_max_reach[i] / ddq_max_[i];
  69. t_f[i] = t_1[i] + std::abs(delta_q_[i]) / dq_max_reach[i];
  70. }
  71. }
  72.  
  73. // take account of the slowest axis
  74. double max_t_f = t_f.maxCoeff();
  75.  
  76. // consider the synchronization of multiple axises
  77. for (size_t i = ; i < ; i++) {
  78. if (std::abs(delta_q_[i]) > DeltaQMotionFinished) {
  79. double a = 3.0 / 2.0 * ddq_max_[i];
  80. double b = -1.0 * max_t_f * std::pow(ddq_max_[i] , 2.0);
  81. double c = std::abs(delta_q_[i]) * std::pow(ddq_max_[i], 2.0);
  82. double delta = b * b - 4.0 * a * c;
  83. if (delta < 0.0) {
  84. delta = 0.0;
  85. }
  86. // according to the area under velocity profile, solve equation "a * Kv^2 + b * Kv + c = 0" for Kv
  87. dq_max_sync_[i] = (-1.0 * b - std::sqrt(delta)) / (2.0 * a); // Kv: maximum synchronization velocity
  88.  
  89. t_1_sync_[i] = 1.5 * dq_max_sync_[i] / ddq_max_[i];
  90. t_f_sync_[i] =(t_1_sync_)[i] + std::abs(delta_q_[i] / dq_max_sync_[i]);
  91. t_2_sync_[i] = (t_f_sync_)[i] - t_1_sync_[i];
  92. q_1_[i] = (dq_max_sync_)[i] * sign_delta_q[i] * (0.5 * (t_1_sync_)[i]);
  93. }
  94. }
  95.  
  96. }
  97.  
  98. bool TrajectoryGenerator::operator()(const RobotState& robot_state, double time)
  99. {
  100. time_ = time;
  101.  
  102. if (time_ == 0.0)
  103. {
  104. q_start_ = Vector7d(robot_state.q_d.data());
  105. delta_q_ = q_goal_ - q_start_;
  106. calculateSynchronizedValues();
  107. }
  108.  
  109. Vector7d delta_q_d;
  110. bool motion_finished = calculateDesiredValues(time_, &delta_q_d);
  111.  
  112. std::array<double, > joint_positions;
  113. Eigen::VectorXd::Map(&joint_positions[], ) = (q_start_ + delta_q_d);
  114.  
  115. return motion_finished;
  116. }

  main.cpp

  1. #define _USE_MATH_DEFINES
  2. #include <math.h>
  3. #include "traj.h"
  4. #include <thread>
  5. #include <iostream>
  6.  
  7. int main(int argc, char *argv[])
  8. {
  9. RobotState current_state;
  10. current_state.q_d = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
  11.  
  12. double speed_factor = 0.5;
  13. std::array<double, > q_goal = { M_PI_4, M_PI_2, 0.0 , 0.0 , 0.0 , 0.0, 0.0 };
  14.  
  15. TrajectoryGenerator traj_generator(speed_factor, q_goal);
  16.  
  17. quint64 count = ;
  18. bool isfinished = false;
  19. while (!isfinished)
  20. {
  21. isfinished = traj_generator(current_state, count / 1000.0);
  22.  
  23. std::this_thread::sleep_for(std::chrono::milliseconds());
  24. count++;
  25. }
  26.  
  27. std::cout << "Motion finished" << std::endl;
  28.  
  29. return ;
  30. }

  注意以下几点:

  1. 原examples_common.h代码中的ddq_max_start_为加速度,ddq_max_goal_为减速度(接近目标点,开始减速),大多数情况下两者相等

  2. 在根据速度曲线与时间轴围成的面积计算最大同步速度的时候,会遇到一元二次方程$a\cdot v_{sync}^2+b\cdot v_{sync}+c=0$求解的问题,对于大于零的两个解要选其中数值小的那个,否则会超过最大速度限制,即取值为$\frac{-b-\sqrt{b^2-4ac}}{2a}$。可以简要证明如下:

  这两个解分布在$v=\frac{-b}{2a}$的两侧,而$\frac{-b}{2a}=\frac{t_{f}k_a}{3}=\frac{1}{3}(\frac{3}{2}\frac{k_v}{k_a}+\frac{|D_j|}{k_v})k_a=\frac{1}{2}k_v+\frac{1}{2}(\frac{2|D_j|k_a}{3k_v})$,根据$|D_j|$的条件 $\frac{2|D_j|k_a}{3k_v}-k_v=\frac{1}{3k_v}(2|D_j|k_a-3k_v^2)> 0$,因此$\frac{-b}{2a}> k_v$,即值较大的解会超出速度限制。

  将时间、轴1轴2的关节角度和速度保存在CSV文件中,用Excel画出散点图。关节角度随时间变化曲线如下(轴1从0→45°,轴2从0→90°):

  关节速度随时间变化曲线如下:

参考:

S型速度规划

线性轨迹的抛物线过渡(梯形加减速)

工业机器人运动轨迹规划方法简述

机器人中的轨迹规划(Trajectory Planning )

周期同步位置模式(CSP),轮廓位置模式(PPM),位置模式(PM)

libfranka MotionGenerator

Robot and interface specifications

Trajectory Planning for Automatic Machines and Robots

Modeling Identification and Control of Robots. 13.3.4 Continuous acceleration profile with constant velocity phase

机器人关节空间轨迹规划--S型速度规划的更多相关文章

  1. 大数据freestyle: 共享单车轨迹数据助力城市合理规划自行车道

    编者按:近年来,异军突起的共享单车极大地解决了人们共同面临的“最后一公里”难题,然而,共享单车发展迅猛,自行车道建设却始终没有能够跟上脚步.幸运的是摩拜单车大量的轨迹数据为我们提供了一种新的思路:利用 ...

  2. 康力优蓝机器人 -- 优友U05类人型机器人发布

    [寒武计划]优友U05类人型机器人发布: http://digi.tech.qq.com/a/20151124/043234.htm?pgv_ref=aio2015&ptlang=2052 北 ...

  3. IT基础架构规划方案一(网络系统规划)

    背景                   某集团经过多年的经营,公司业务和规模在不断发展,公司管理层和IT部门也认识到通过信息化手段可以更好地支撑公司业务运营.提高企业生产和管理效率.同时随着新建办公 ...

  4. 【2018.04.19 ROS机器人操作系统】机器人控制:运动规划、路径规划及轨迹规划简介之一

    参考资料及致谢 本文的绝大部分内容转载自以下几篇文章,首先向原作者致谢,希望自己能在这些前辈们的基础上能有所总结提升. 1. 运动规划/路径规划/轨迹规划的联系与区别 https://blog.csd ...

  5. Matlab Robotics Toolbox 仿真计算:Kinematics, Dynamics, Trajectory Generation

    1. 理论知识 理论知识请参考: 机器人学导论++(原书第3版)_(美)HLHN+J.CRAIG著++贠超等译 机器人学课程讲义(丁烨) 机器人学课程讲义(赵言正) 2. Matlab Robotic ...

  6. V-rep学习笔记:机器人路径规划1

     Motion Planning Library V-REP 从3.3.0开始,使用运动规划库OMPL作为插件,通过调用API的方式代替以前的方法进行运动规划(The old path/motion ...

  7. 机器人路径规划其一 Dijkstra Algorithm【附动态图源码】

    首先要说明的是,机器人路径规划与轨迹规划属于两个不同的概念,一般而言,轨迹规划针对的对象为机器人末端坐标系或者某个关节的位置速度加速度在时域的规划,常用的方法为多项式样条插值,梯形轨迹等等,而路径规划 ...

  8. 机器人路径规划其二 A-Star Algorithm【附动态图源码】

    首先要说明的是,机器人路径规划与轨迹规划属于两个不同的概念,一般而言,轨迹规划针对的对象为机器人末端坐标系或者某个关节的位置速度加速度在时域的规划,常用的方法为多项式样条插值,梯形轨迹等等,而路径规划 ...

  9. 如何用MoveIt快速搭建机器人运动规划平台?

    MoveIt = RobotGo,翻译成中文就是“机器人,走你!”所以,MoveIt的主要就是一款致力于让机器人能够自主运动及其相关技术的软件,它的所有模块都是围绕着运动规划的实现而设计的. 两个月前 ...

随机推荐

  1. objectmapper使用

    https://www.cnblogs.com/liam1994/p/5629356.html

  2. 关于go get安装git golang项目时报错的处理办法

    关于go get安装git golang项目时报错的处理办法 使用go get安装github上的项目时一般来说,不可避免会出错.各种错误的处理办法: 必须条件: 1.安装git并配置环境变量.下载地 ...

  3. 用Eclipse上传项目到github

    1.安装EGit插件 点击菜单栏help->Eclipse Marketplace 2.配置Git 这里是配置相关账户信息 3.把项目提交到本地仓库 右键项目->Team->Shar ...

  4. Codeforces 1037D【BFS】

    <题目链接> 题目大意: 给你一颗树的所有边,这些边是无向的,然后给你一段BFS序列,BFS都以1为根节点,判断这段BFS序列是否合法. 解题分析: 就是模拟BFS,某个父亲节点的所有子节 ...

  5. 006.Ceph对象存储基础使用

    一 Ceph文件系统 1.1 概述 Ceph 对象网关是一个构建在 librados 之上的对象存储接口,它为应用程序访问Ceph 存储集群提供了一个 RESTful 风格的网关 . Ceph 对象存 ...

  6. ISP PIPLINE(零) 知识综述预热

    本文为camera isp pipline概述 ISP,即image signal processing.为图像成型做的处理工作.适应不同光学环境下图像的还原. pipline流程如下: 光通过LEN ...

  7. 虚幻开放日2017ppt

    虚幻开放日2017ppthttp://pan.baidu.com/s/1c1SbcKK 如果挂了QQ+378100977 call我

  8. 【DWM1000】 非官方开源定位代码bitcraze

    蓝点DWM1000 模块已经打样测试完毕,有兴趣的可以申请购买了,更多信息参见 蓝点论坛 正文: 最近关注DWM1000 定位,一方面在看DWM1000 官方提供的代码,也在四处网上找资料看资料. 其 ...

  9. STM32——C语言课堂原代码

    指针 /* ============================================================================ Name : Hello.c Au ...

  10. Java中类加载过程和对象创建过程

    类加载过程: 1, JVM会先去方法区中找有没有相应类的.class存在.如果有,就直接使用:如果没有,则把相关类的.class加载到方法区 2, 在.class加载到方法区时,会分为两部分加载:先加 ...