
Path $\theta(s)$: a geometric sequence of configuration $\theta$ with respect to a geometric path parameter $s$.
●$s\in[0,1]$. (0-100%)
●Shows how the configuration changes from where it starts, through its intermediate values, and to where it ends.
●e.g. $\theta(s)$ for a revolute joint configuration, $x(s)$ for a task space configuration, etc.
Time scaling $s(t)$: a mapping time $t$ to $s$. A time parameter.
●$t\in[0,T]$. $T$ is the duration.
※$t\in[T_{0}, T_{f}]$ ($T_{0}$: initial time, $T_{f}$: final time), you can use this $s(t)$ but the time scaling equations in this chapter will need to be modified accordingly.
Trajectory $\theta(s(t))$ or $\theta(t)$: It shows how the configuration $\theta$ changes with respect to time $t$.
●Path + Time scaling → Trajectory
●Dynamically well-defined(that ensure the acceleration) trajectory consist of twice differentiable path($\frac{d^{2} \theta}{ds^2}$) and time scaling($\frac{d^{2} s}{dt^2}$)

Point-to-Point Trajectory
Path
Joint space($\theta$) straight line: $\theta(s)=\theta_{start}+s(\theta_{end}-\theta_{start})$, $s\in[0,1]$
●Joint limit: $\theta_{min}<\theta<\theta_{max}$
Task space($X$) point-to-point:
●There might be unreachable sections on the joint space path due to the inverse kinematics or the joint limits.
For explicit representation $X=[x,y,z,\phi,\theta,\psi]\in\mathbb{R}^{6}$
●$X(s)=X_{start}+s(X_{end}-X_{start})$, $s\in[0,1]$
For implicit representation $X\in SE(3)$, there are two ways ①②.
①Utilize the screw motion
$X(s)=X_{start}T(s)=X_{start}\text{exp}(\text{log}(X_{start,end})s)=X_{start}\text{exp}(\text{log}(X_{start}^{-1}X_{end})s)$, $s\in[0,1]$
●Though it's a point-to-point path, the origin doesn't follow a straight line since it's the screw motion.
②Decouple position and rotation $X=[p,R]^{T}$, $p=[x,y,z]\in\mathbb{R}^{6}$, $R\in SO(3)$
$p(s)=p_{start}+s(p_{end}-p_{start})$, $R(s)=R_{start}\text{exp}(\text{log}(R_{start}^{-1}R_{end})s)$, $s\in[0,1]$
●The origin follows a straight line between the start and end position.
Time scaling
3rd-order polynomial(Cubic spline): define time scaling with start and end position, velocity.
$s(t)=a_0+a_1t+a_2t^2+a_3t^3$
●For $t\in[0,T], s(0)=0, \dot{s}(0)=0, s(T)=1, \dot{s}(T)=0$
$a_0=a_1=0, a_2=\frac{3}{T^2},a_3=-\frac{2}{T^3} $
●For $t\in[t_s,t_e], s(t_s)=0, \dot{s}(t_s)=0, s(t_e)=1, \dot{s}(t_e)=0$
$a_0=a_1=0, a_2=\frac{3}{(t_e-t_s)^2},a_3=-\frac{2}{(t_e-t_s)^3}$
5th-order polynomial(Quintic spline): define time scaling with start and end position, velocity, acceleration.
$s(t)=a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5$
●For $t\in[t_s,t_e], s(t_s)=0, \dot{s}(t_s)=0, \ddot{s}(t_s)=0, s(t_e)=1, \dot{s}(t_e)=0$, \ddot{s}(t_e)=0
$a_0=a_1=0, a_2=0,a_3= \frac{10}{(t_e-t_s)^3} , a_4=-\frac{15}{(t_e-t_s)^4}, a_5=\frac{6}{(t_e-t_s)^5} $
●Smoother motion, a higher maximum velocity than a cubic spline.

Trapezoidal motion (velocity) profile

●Starts with constant acceleration $a$, followed by constant velocity phase, and decelerates with $-a$.
●Generally used for the control of a single motor joint.
●Not as smooth as the cubic spline.
●Given joint velocity and acceleration limits, the trapezoidal motion profile makes the fastest motion respecting the limits.(Using $a=a_{max}, v=v_{max}$)
S-curve time scaling
●Improve the trapezoidal motion profile so as not to have infinite jerk.
Via points Trajectory
●Given $k$ via points(including the start and end points), the trajectory is divided into $k-1$ segments(subtrajecotry).
●Connect each segment using polynomial interpolation.
●The trajectory is ensured to be through the via points.
●Some parts of the trajectory may be out of the convex hull of the via points.
3rd-order polynomial(Cubic spline)
●Each via point has the desired velocity.
●The end position and velocity of a via point will be the start position and velocity of the following via point.
$\theta_{i,e}=\theta_{i+1,s}$, $\dot{\theta}_{i,e}=\dot{\theta}_{i+1,s}$
5th-order polynomial(Quintic spline)
●Each via point has the desired velocity and acceleration.
●The end position, velocity, and acceleration of a via point will be the start position, velocity, and acceleration of the following via point.
$\theta_{i,e}=\theta_{i+1,s}$, $\dot{\theta}_{i,e}=\dot{\theta}_{i+1,s}$, $\ddot{\theta}_{i,e}=\ddot{\theta}_{i+1,s}$
B-spline interpolation
●The trajectory is not ensured to be through the via points.
●The trajectory must be confined to the convex hull of the via points.

========================================================================
정확한 정보 전달보단 공부 겸 기록에 초점을 둔 글입니다.
틀린 내용이 있을 수 있습니다.
틀린 내용이나 다른 문제가 있으면 댓글에 남겨주시면 감사하겠습니다. : )
========================================================================
'공부 > Modern Robotics' 카테고리의 다른 글
| [Modern Robotics] 강좌 3: 로봇 동역학 #5 (0) | 2025.01.03 |
|---|---|
| [Modern Robotics] 강좌 3: 로봇 동역학 #3 (0) | 2024.12.11 |
| [Modern Robotics] 강좌 3: 로봇 동역학 #2 (1) | 2024.12.11 |
| [Modern Robotics] 강좌 3: 로봇 동역학 #1 (0) | 2024.12.06 |
| [Modern Robotics] 강좌 2: 로봇 기구학 #2 (0) | 2024.12.04 |