cohen

cohen

A man who want to make the world better.

NCKU Advanced Robotics Control Course Notes - Twist (Spatial Velocity)

Most of the robots in our reality can be considered as combinations of rigid bodies, so let's first discuss the velocity of rigid bodies.

The Connection and Difference Between Physical Quantities and Numbers#

In the abstract world of physics, we believe that there are two real entities: points and vectors.

A point is the abstract representation of physical quantities in the physical world, existing independently of any coordinate system.

The position of a rigid body can be abstracted as a point; regardless of whether a coordinate system is established or what kind of coordinate system is established, the position of the robot will not change. As long as the rigid body itself is at rest, its position (point) in the physical world is fixed.

A vector is also an abstract representation of physical quantities in the physical world, but unlike a point, it has magnitude and direction.

The velocity and acceleration of a rigid body are vectors. Similarly, regardless of how the coordinate system changes, the vectors represented by velocity and acceleration will not change.

One point to note here is that the coordinate system I am referring to is not the same as the reference frame we learned in high school physics.
![[The Difference and Connection Between Coordinate Systems and Reference Frames in Robot Research#Example of Mobile Robots]]

When we use physical laws to express and calculate physical quantities, and we do not care about the specific magnitude of the physical quantities, but only about the relationships between physical quantities, we do not need a coordinate system or numbers.

A particle $b$ is moving in space, and we can describe its velocity with a vector vbv_b, while we can use the composition and decomposition of velocity physical law to arbitrarily select two vectors such that vb1+vb2=vbv_{b_1} + v_{b_2} = v_b.
We can say that the particle bb has a velocity vbv_b, moving at a speed of vb|v_b| in the direction of vbv_b.
We can also say that the particle bb has two velocities vb1v_{b_1} and vb2v_{b_2}.

In the above example, we did not use a coordinate system or numbers; we used a physical law to express the relationship between three vectors with symbols, while also explaining their physical meaning.

For points and vectors, we always need to care about where the point is, what the magnitude of the vector is, and what the direction of the vector is when applying them.

In practical applications, we certainly want to know where the robot's position is, what its speed is, and what direction it is moving, etc.

At this point, we need to define a coordinate system, from which we can represent physical quantities with numbers rather than just symbols.

Velocity of Rigid Bodies#

First, we need to clarify what exactly is the velocity of a rigid body?

Before studying this course, my intuitive understanding of the velocity of a rigid body was simply the velocity of the center of mass of the rigid body and the angular velocity of the rigid body rotating around the axis through the center of mass; together, they constitute the velocity of the rigid body.

This is clearly not accurate enough, so here we need to first define the velocity of a rigid body.

First, we know that a rigid body is composed of infinitely many points. At the same time, we know that the velocity of these points within the rigid body is related to their position within the rigid body and other parameters (such as the angular velocity of the rigid body around an axis).

Therefore, we can express the velocity of any point pip_i in the rigid body in the form of an implicit function as vpi=f(pi,parameters)v_{p_i}=f(p_i, \text{parameters}).

Based on this form, we define the velocity of a rigid body as the parameters\text{parameters} here.

In other words, as long as we know the velocity of the rigid body and the coordinates of a point on the rigid body, we can calculate the velocity of that point.

In practice, we generally do not care about the velocity of the rigid body. We care about the end-effector velocity of the robotic arm, the velocity of the geometric center of the vehicle, the velocity of the center point on the body of the quadruped robot, etc.
However, if we calculate the velocity of the rigid body from the beginning, we can conveniently calculate the velocities of all the points we want.
Conversely, if we only calculate one point at the beginning and later want to calculate other points, it will become troublesome and confusing.

Of course, up to this point, it is still too abstract. Next, we will expand and explain step by step until we reach spatial velocity.

image

As shown in Figure 1, the rigid body is rotating around a fixed axis, and we choose a point p0p_0 on the rotation axis of the rigid body as the reference point. According to the relationship between angular velocity and linear velocity in high school physics, we can know that for any point pip_i in the rigid body, vpi=ω×p0piv_{p_i}=\omega \times \overrightarrow{p_0p_i}.

Then, to make our discussion more universal, let's take a step further. Suppose the rotation axis of the rigid body is not fixed but is moving.

image

p0p_0 is still a point on the rotation axis of the rigid body, and we choose p0p_0 as the reference point to describe the velocity of the particle. For any point pip_i in the rigid body, we have vpi=vp0+ω×p0piv_{p_i}=v_{p_0} + \omega \times \overrightarrow{p_0p_i}.

Again, we remind you that our current description is all about the relationships between vectors, so it does not involve any coordinate systems, which also means that these relationships hold in any coordinate system.

From a physical perspective, let's see how vpi=vp0+ω×p0piv_{p_i}=v_{p_0} + \omega \times \overrightarrow{p_0p_i} is derived.

First, essentially, the velocity of a point is the change in position of that point, which is its derivative, i.e., vpi=pi˙v_{p_i}=\dot{p_i}. Similarly, vp0=p0˙v_{p_0}=\dot{p_0}.

Next, for convenience of understanding, let's set the origin of the coordinate system as oo. According to the principle of vector composition (yes, you are not mistaken, this is a physical law! Not a mathematical rule), we must have opi=op0+p0pi\overrightarrow{op_i}=\overrightarrow{op_0}+\overrightarrow{p_0p_i}.

At the same time, since the rigid body is in motion, points pip_i and p0p_0 are changing with time. And at any time tt, we have opi(t)=op0(t)+p0pi(t)\overrightarrow{op_i}(t)=\overrightarrow{op_0}(t)+\overrightarrow{p_0p_i}(t).

In our subsequent symbolic representation, pip_i and opi\overrightarrow{op_i} mean the same thing; using pip_i mainly emphasizes that it is independent of the coordinate system, and its relationship with other vectors and points is also independent of the coordinate system.

Therefore, we have pi(t)=p0(t)+p0pi(t)p_i(t)=p_0(t)+\overrightarrow{p_0p_i}(t). Taking the derivative of both sides gives pi˙=p0˙+(p0pi)\dot{p_i}=\dot{p_0}+(\overrightarrow{p_0p_i})'. Ultimately, we can obtain vpi=vp0+ω×p0piv_{p_i}=v_{p_0} + \omega \times \overrightarrow{p_0p_i}.

The length of p0pi\overrightarrow{p_0p_i} in (p0pi)(\overrightarrow{p_0p_i})' has not changed (because these two points are within the rigid body, and the rigid body does not undergo deformation), only the direction has changed.
The derivative of the vector p0pi\overrightarrow{p_0p_i} is ω×p0pi\omega \times \overrightarrow{p_0p_i}.
From a physical perspective, ω×p0pi\omega \times \overrightarrow{p_0p_i} represents the linear velocity brought to point pip_i by the angular velocity ω\omega.
{ps: This can be easily understood by drawing and using the basic definition of derivatives.}

We can see that the difference between vpi=vp0+ω×p0piv_{p_i}=v_{p_0} + \omega \times \overrightarrow{p_0p_i} and vpi=ω×p0piv_{p_i}= \omega \times \overrightarrow{p_0p_i} is whether vp0=0v_{p_0}=0 or not.

Thus, whether the rigid body is performing pure rolling in space or not, the relationship between the velocity of any point in the rigid body and the velocity of the reference point p0p_0 satisfies vpi=vp0+ω×p0pi v_{p_i}=v_{p_0} + \omega \times \overrightarrow{p_0p_i}.

Combining vpi=vp0+ω×p0piv_{p_i}=v_{p_0} + \omega \times \overrightarrow{p_0p_i} with the implicit function expression vpi=f(pi,parameters)v_{p_i}=f(p_i, \text{parameters}), we can conclude that at this time, the velocity of the rigid body is (vp0,ω)(v_{p_0}, \omega).

Reviewing the previous text:
We can express the velocity of any point pip_i in the rigid body in the form of an implicit function as vpi=f(pi,parameters)v_{p_i}=f(p_i, \text{parameters}). Based on this form, we define the velocity of a rigid body as the parameters\text{parameters} among them.

image

As shown in Figure 2, let's continue to take the second step, we choose any point qq on the rigid body as the reference point for expressing velocity.

The significance of this step is: to broaden the range of reference points we can choose in the expression of rigid body velocity, proving that our reference point does not necessarily have to be on the rotation axis.

Choosing a reference point on the rotation axis is naturally convenient because we do not have to consider the issue of the reference point rotating.

However, in practical engineering, we often cannot directly obtain the velocity of the rotation axis.
We can only place the velocity measurement sensor in a suitable position on the machine and cannot always install it on the rotation axis.

CallBack:
As long as we know the velocity of the rigid body and the coordinates of a point on the rigid body, we can calculate the velocity of that point.
The ability to choose reference points more broadly allows us to calculate the velocity of the rigid body well in many imperfect real situations.

Thus, we have vpi=vq+ω×qpi v_{p_i}=v_{q} + \omega \times \overrightarrow{qp_i}.
Let's continue to derive this equation using physical laws.

For point qq, we have vq=vp0+ω×p0q(3) v_{q}=v_{p_0} + \omega \times \overrightarrow{p_0q} \quad\text{(3)}.
For point pip_i, we have vpi=vp0+ω×p0pi(4) v_{p_i}=v_{p_0} + \omega \times \overrightarrow{p_0p_i} \quad\text{(4)}.

From the equations (4)(3)(4) - (3), we can derive:

vpi=vq+ω×p0piω×p0qvpi=vq+ω×(p0pip0q)vpi=vq+ω×qpi\begin{gathered} v_{p_i}=v_{q} + \omega \times \overrightarrow{p_0p_i} - \omega \times \overrightarrow{p_0q} \\ v_{p_i}=v_{q} + \omega \times (\overrightarrow{p_0p_i} - \overrightarrow{p_0q}) \\ v_{p_i}=v_{q} + \omega \times \overrightarrow{qp_i} \end{gathered}

Similarly, based on the definition of rigid body velocity, at this time, the velocity of the rigid body is (vq,ω)(v_{q}, \omega).

CallBack:
We can express the velocity of any point pip_i in the rigid body in the form of an implicit function as vpi=f(pi,parameters)v_{p_i}=f(p_i, \text{parameters}). Based on this form, we define the velocity of a rigid body as the parameters\text{parameters} among them.

Now that we have completed all the foundational parts.

image

Next, we need to take an important third step. As shown in Figure 3, we randomly select a body-fixed point qq' outside the rigid body.

The significance of this step is: to further broaden the range of reference points we can choose in the expression of rigid body velocity, proving that our reference point does not necessarily have to be on the rigid body, as long as it is body-fixed.

In the previous second step, we chose any point on the rigid body; now we are choosing any point outside the rigid body but body-fixed. The meaning of these two is completely the same, with the key being body-fixed.

The concept of "field" in physics can help understand body-fixed.
For example, in the magnetic field of a magnet, if we select a point A in the magnetic field of a magnet, then although this point is not on the magnet, it will still move with the magnet, which is what is meant by body-fixed.

Therefore, based on the results of the second step, we can still obtain vpi=vq+ω×qpi(5) v_{p_i}=v_{q'} + \omega \times \overrightarrow{q'p_i} \quad\text{(5)}.
To repeat, at this time, the velocity of the rigid body in the figure is (vq,ω)(v_{q'}, \omega).

Now, let's move on to the final fourth step: to reach the limit of the range of reference points we can choose in the expression of rigid body velocity, proving that our reference point does not necessarily have to be body-fixed. It can be any point, whether it is moving or not, whether it is body-fixed or not, etc..

image

We choose a coordinate system {A}\{A\}, and we can say that at every moment, there is a body-fixed point coinciding with the origin OAO_A of the coordinate system {A}\{A\}.

We define: The mathematical symbol vOA(t)v_{O_A}(t) represents the velocity of the body-fixed point qq' that coincides with point OAO_A at time t.

This statement is very important: The symbol vOA(t)v_{O_A}(t) represents the velocity of the body-fixed point qq' that coincides with point OAO_A at time t.

Not the velocity of point OAO_A; I do not care about the velocity of point OAO_A, regardless of what it is.

Thus, based on equation (5), we replace vqv_{q'} with vOAv_{O_A}: vpi=vOA+ω×OApi(6) v_{p_i}=v_{O_A} + \omega \times \overrightarrow{O_Ap_i} \quad\text{(6)}.
Since point OAO_A is the origin, if I express this equation in the coordinate system {A}\{A\}, it can be written as Avpi=AvOA+Aω×AOApi(6)^{A}v_{p_i}=^{A}v_{O_A} + ^{A}\omega \times ^{A}\overrightarrow{O_Ap_i} \quad\text{(6)}.
Avpi=AvOA+Aω×Api(7)^{A}v_{p_i}=^{A}v_{O_A} + ^{A}\omega \times ^{A}p_i \quad\text{(7)}.

For the last time, based on the definition of rigid body velocity, we can conclude that at this time, the velocity of the rigid body is (vOA,ω)(v_{O_A}, \omega).

You should feel that this (vOA,ω)(v_{O_A}, \omega) is very counterintuitive; it is certainly not the velocity of the center of mass of the rigid body in the XYZ direction combined with the angular velocity around XYZ. It feels "very unlike" the velocity of a rigid body...
The sacrifice of intuition is valuable; with this, we will find it very convenient when calculating the forward and inverse kinematics of multi-rigid-body structured robots later.

In textbooks, the naming of (vOA,ω)(v_{O_A}, \omega) is spatial velocity or twist.

Seeing this, you may still be a bit confused, so let's provide a couple more examples.

image

Let ω=50rad/s\omega = 50 \> rad/s, OBOA=0.04|\overrightarrow{O_BO_A}| = 0.04. The coordinate system {A}\{A\} is the fixed world coordinate system, and the coordinate system {B}\{B\} rotates with the cone.

Note that ω=50rad/s\omega = 50 rad/s means the angular velocity of the cone relative to the world coordinate system.

First, let's look at the spatial velocity of the cone in the coordinate system {A}\{A\}: Aν=(AωAvOA)^{A}\nu=\left( \begin{array} {ccc} ^{A}\omega\\ ^{A}v_{O_A} \end{array} \right).
Naturally, Aω=(0050)^{A}\omega = \left( \begin{array} {ccc} 0\\ 0 \\ 50 \end{array} \right). Now, what is AvOA^{A}v_{O_A}?

CallBack:
The symbol vOA(t)v_{O_A}(t) represents the velocity of the body-fixed point qq' that coincides with point OAO_A at time t.

So, we can directly find this body-fixed point qq'.

The body-fixed point and the point on the rigid body are completely equivalent; they both move with the rigid body.

So, how do we find the velocity of the point qq' on the rigid body? We can directly apply equation (5): vq=vr+ω×rq v_{q'}=v_{r} + \omega \times \overrightarrow{rq'},
where vrv_r is the reference point velocity, and rr is the reference point.

Note that velocity vv and spatial velocity ν\nu are not the same.

We can choose a convenient reference point OBO_B to easily find vqv_{q'}, because we know that vOBv_{O_B} is zero.

The cone is only rotating, not translating, so vOBv_{O_B} is zero. ps: this vOBv_{O_B} refers to the velocity of the body-fixed point OBO_B on the rigid body.
Since we are expressing the spatial velocity in the {A}\{A\} coordinate system, only vOAv_{O_A} is special.
Again, CallBack:
The symbol vOA(t)v_{O_A}(t) represents the velocity of the body-fixed point qq' that coincides with point OAO_A at time t, not the velocity of point OAO_A.

Thus, we can obtain Avq=AvOB+Aω×AOBq ^{A}v_{q'}=^{A}v_{O_B} + ^{A}\omega \times \overrightarrow{^{A}O_Bq'}.
Don't forget! Our Avq^{A}v_{q'} here is actually what we defined as AvOA^{A}v_{O_A}.

AvOA=AvOB+Aω×AOBOAAvOA=Aω×AOBOAAvOA=(0050)×(00.040)AvOA=(200)\begin{align} ^{A}v_{O_A}&=^{A}v_{O_B} + ^{A}\omega \times ^{A}\overrightarrow{O_BO_A} \\ ^{A}v_{O_A}&= ^{A}\omega \times ^{A}\overrightarrow{O_BO_A} \\ ^{A}v_{O_A}&= \left( \begin{array} {ccc} 0 \\ 0 \\ 50 \end{array} \right) \times \left( \begin{array} {ccc} 0 \\ -0.04 \\ 0 \end{array} \right) \\ ^{A}v_{O_A}&= \left( \begin{array} {ccc} 2 \\ 0 \\ 0 \end{array} \right) \end{align}

Thus, we have obtained the spatial velocity representation of the rigid body cone, which is expressed as Aν=(0050200)^{A}\nu=\left( \begin{array} {ccc} 0 \\ 0 \\ 50 \\ 2 \\ 0 \\ 0 \end{array} \right) in the coordinate system {A}\{A\}.
Next, let's calculate the velocity of the rigid body cone in the coordinate system {B}\{B\}.

CallBack:
Note that the velocity of the cone we are describing is always relative to the world coordinate system.

We are just changing the mathematical representation of this already existing physical quantity in different coordinate systems.

Bν=(BωBvOA)^{B}\nu=\left( \begin{array} {ccc} ^{B}\omega\\ ^{B}v_{O_A} \end{array} \right).
First, for Bω^{B}\omega, from the figure, we can see that Aω^{A}\omega rotates around the $\widehat{z}$ axis, while Bω^{B}\omega rotates around the $\widehat{x}$ axis. Therefore, Bω=(5000)^{B}\omega = \left( \begin{array} {ccc} 50\\ 0 \\ 0 \end{array} \right).

From the figure, we can see that throughout the entire process of the cone's rotation, all points that are body-fixed to this cone have remained unchanged, always being the apex of the cone, and it has neither rotated nor translated. Thus, BvOA=(000)^{B}v_{O_A} = \left( \begin{array} {ccc} 0\\ 0 \\ 0 \end{array} \right).
In summary, Bν=(5000000)^{B}\nu=\left( \begin{array} {ccc} 50\\ 0 \\0 \\0\\0\\0 \end{array} \right).
At this point, we can introduce an important knowledge point: coordinate transformation.

Since we are only expressing the same physical vector in different coordinate systems, how should these different representations of coordinate systems be transformed? This is beneficial for converting the physical quantities we care about into coordinate systems that are easier for calculation or coding.

[[Todo: Coordinate Transformation of Twists]]

Let's take another example of a mobile robot.

image

The figure describes a mobile robot rotating around the center point rr, where the coordinates of point rr in coordinate system {s}\{s\} are sr=(2,1,0)^{s}r = (2,-1,0), and in coordinate system {b}\{b\}, the coordinates are br=(2,1.4,0)^{b}r=(2,-1.4,0). The angular velocity of rotation is ω=2rad/s\omega = 2 \> rad/s.

There are two coordinate systems in the figure: the world coordinate system {s}\{s\} and the body coordinate system {b}\{b\}. Both follow the right-hand rule, where the zz axis of {s}\{s\} points out of the paper, and the zz axis of {b}\{b\} is opposite to it.

Similar to the cone example, let's first look at the spatial velocity sν=(sωsv)^{s}\nu=\left( \begin{array} {ccc} ^{s}\omega\\ ^{s}v \end{array} \right) in coordinate system {s}\{s\}.

Here, the symbol sv^{s}v is synonymous with svOs^{s}v_{O_s}; in the future, if not explicitly needed, we will use sv^{s}v to represent svOs^{s}v_{O_s}.

Where sω=(002)^{s}\omega = \left( \begin{array} {ccc} 0\\ 0 \\ 2 \end{array} \right),

sv=vr+sω×srOssv=0+ω×(sr)sv=(002)×(210)sv=(240)\begin{align}^{s}v &= v_r + ^{s}\omega \times \overrightarrow{^{s}rO_{s}} \\^{s}v&=0 + \omega \times (-^{s}r) \\^{s}v&= \left( \begin{array} {ccc} 0\\ 0 \\ 2 \end{array} \right) \times \left( \begin{array} {ccc} -2\\ 1 \\ 0 \end{array} \right)\\ ^{s}v&= \left( \begin{array} {ccc} -2\\ -4 \\ 0 \end{array} \right)\end{align}

Now let's calculate the spatial velocity in coordinate system {b}\{b\}, and the answer is (try to calculate it by hand as practice) bν=(0022.840)^{b}\nu=\left( \begin{array} {ccc} 0\\ 0\\-2\\2.8\\4\\0 \end{array} \right).

Loading...
Ownership of this post data is guaranteed by blockchain and smart contracts to the creator alone.