Yes. Using the theorem presented in Class 4:
$$\dot{Q}(t) = S(\omega(t))Q(t).$$Applying the determinant on both sides and using the Binet's Theorem, which states that for two square matrices \(U\) and \(V\), \(\det(UV) = \det(U)\det(V)\):
$$\det(\dot{Q}) = \det(S(\omega))\det(Q).$$Every odd-order antisymmetric matrix has a determinant of 0. Therefore, since \(S(\omega)\) is a three-dimensional matrix, we arrive at our result.
No, for the particle to have zero velocity:
$$v + \omega \times (p-s) = 0$$where \(p\) is the position of the particle and \(s\) is the position of the center.
Remember that \(a \times b\) is always mutually orthogonal to \(a\) and \(b\).
So \(\omega \times (p-s)\) is orthogonal to \(\omega\), and since \(\omega\) is parallel to \(v\), \(\omega \times (p-s)\) is orthogonal to \(v\)
The sum of two orthogonal vectors is only zero if both are zero. Since \(v\) is non-zero, this is impossible in this case.
Yes. Using the theorem presented in Class 4:
$$\dot{Q}(t) = S(\omega(t))Q(t).$$If we divide \(Q(t)\) into its columns \(x(t), y(t), z(t)\), we will see that this equality implies that \(\dot{x} = S(\omega)x, \dot{y} = S(\omega)y\) and \(\dot{z} = S(\omega)z\).
Using Property 2 from Class 4, \(\dot{z} = S(\omega)z\ = \omega \times z\).
Since the cross product of two vectors is orthogonal to both, \(\dot{z}\) and \(\omega\) are orthogonal.
Yes. Due to the restriction that \(A^T=-A\) for an antisymmetric matrix, we can see by inspection that we only have the freedom to choose 3 numbers in this matrix.
In any way we choose these three numbers, it will be the matrix \(S\) of some three-dimensional vector.
Yes. Suppose \(a\) is a non-zero vector. Using Property 2 from Class 4, if we choose \(b=a\), we have \(S(a)b = S(a)a = a \times a = 0_{3 \times 1}\) (property of the cross product).
If \(a\) is the zero vector, \(S(a)\) is the zero matrix, and we can choose any non-zero vector \(b\).
For this, we use the triangle inequality, which states that for any vectors \(a\) and \(b\):
$$\|a+b\| \leq \|a\| + \|b\|$$And also the fact that
$$\|a \times b \| = \|a\| \|b\| \sin(\theta) \leq \|a\| \|b\|$$where \(\theta\) is the angle between the vectors \(a\) and \(b\), always between 0 and 180 degrees.
Since the velocity of any particle \(G\) is \(v_G = v+ \omega \times (p^G-s)\), applying these two properties:
$$\|v_G\| \leq \|v\| + \|\omega\|\|p^G-s\|.$$But \(\|p^G-s\|\) is the distance of the particle to the center \(P\), which is always less than the radius \(R\) (due to the definition of this radius). Hence, we conclude our result.
(a) Let \(c_A = \cos(\omega_At), s_A = \sin(\omega_At)\), \(c_{AD} = \cos((\omega_A+\omega_D)t)\) and \(s_{AD} = \sin((\omega_A+\omega_D)t)\). Using the expression of \(R_0^T(t)\) found in the problem solution, we can extract:
$$s = \LARGE{\Bigg(}\normalsize{}\begin{array}{c} d_T c_A \\ d_T s_A \\ 0 \end{array}\LARGE{\Bigg)}\normalsize{} \ , \ Q = \LARGE{\Bigg(}\normalsize{}\begin{array}{ccc} c_{AD} & -s_{AD} & 0 \\ s_{AD} & \ c_{AD} & 0 \\ 0 & 0 & 1 \end{array}\LARGE{\Bigg)}.$$Then, using the formula \(v = \dot{s}\) and \(S(\omega) = \dot{Q}Q^T\):
$$v = \LARGE{\Bigg(}\normalsize{}\begin{array}{c} -\omega_A d_T s_A \\ \ \omega_A d_T c_A \\ 0 \end{array}\LARGE{\Bigg)}\normalsize{} \ , \ \omega = \LARGE{\Bigg(}\normalsize{}\begin{array}{c} 0 \\ 0 \\ \omega_D \end{array}\LARGE{\Bigg)}.$$(b) Let \(c_0 = \cos(\omega_0t), s_0 = \sin(\omega_0t)\), \(c_{1} = \cos(\omega_1t)\) and \(s_{1} = \sin(\omega_1t)\). Using the expression of the HTM found in the problem solution, we can extract:
$$s = \LARGE{\Bigg(}\normalsize{}\begin{array}{c} (d_0+d_1c_1)c_0 \\ (d_0+d_1c_1)s_0 \\ -d_1s_1 \end{array}\LARGE{\Bigg)}\normalsize{} \ , \ Q = \LARGE{\Bigg(}\normalsize{}\begin{array}{ccc} c_0c_1 & -s_0 & c_0s_1 \\ s_0c_1 & \ c_0 & s_0s_1 \\ -s_1 & 0 & c_1 \end{array}\LARGE{\Bigg)}.$$Then, using the formula \(v = \dot{s}\) and \(S(\omega) = \dot{Q}Q^T\):
$$v = \LARGE{\Bigg(}\normalsize{}\begin{array}{c} -d_1 \omega_1s_1c_0{-}(d_0{+}d_1c_1)\omega_0s_0 \\ -d_1 \omega_1s_1s_0{+}(d_0{+}d_1c_1)\omega_0c_0 \\ -d_1\omega_1c_1 \end{array}\LARGE{\Bigg)}\normalsize{} \ , \ \omega = \LARGE{\Bigg(}\normalsize{}\begin{array}{c} -\omega_1 s_0 \\ \ \omega_1c_0 \\ \ \omega_0 \end{array}\LARGE{\Bigg)}.$$From the relation \(\frac{d}{dt} s(q) = J_v(q)\dot{q}\), we have:
$$J_v(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} -(1{+}q_2)s_1{-}c_1 & c_1 \\ \ \ (1{+}q_2)c_1{-}s_1 & s_1 \\ 0 & 0 \end{array}\LARGE{\Bigg)}\normalsize{}.$$From the relation \(S(\omega) = \dot{Q}(t)Q(t)^T\) and \(\omega = J_\omega(q)\dot{q}\), we have:
$$J_\omega(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} 0 & 0 \\ 0 & 0 \\ 1 & 0 \end{array}\LARGE{\Bigg)}\normalsize{}.$$We start by extracting the following elements:
$$z_{DH0}(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} 1 \\ 0 \\ 0 \end{array}\LARGE{\Bigg)}\normalsize{} \ , \ s_{DH0}(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} 0 \\ 0 \\ 0 \end{array}\LARGE{\Bigg)}\normalsize{} \ (\mbox{from} \ H_{0}^{DH0})$$ $$z_{DH1}(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} 1 \\ 0 \\ 0 \end{array}\LARGE{\Bigg)}\normalsize{} \ , \ s_{DH1}(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} 0 \\ 0{,}3c_1 \\ 0{,}3s_1 \end{array}\LARGE{\Bigg)}\normalsize{} \ (\mbox{from} \ H_{0}^{DH1}(q))$$And also:
$$z_{DH2}(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} 0 \\ -s_{12} \\ \ c_{12} \end{array}\LARGE{\Bigg)}\normalsize{} \ , \ s_{DH2}(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} 0 \\ 0{,}3c_1{+}0{,}25c_{12}\\ 0{,}3s_1{+}0{,}25s{12} \end{array}\LARGE{\Bigg)}\normalsize{} \ (\mbox{from} \ H_{0}^{DH2}(q))$$ $$s_e(q) = \LARGE{\Bigg(}\normalsize{}\begin{array}{cc} -0{,}2s_3 \\ (0{,}2c_3+0{,}25)c_{12} {+} 0{,}3c_1 \\ (0{,}2c_3+0{,}25)s_{12} {+} 0{,}3s_1 \end{array}\LARGE{\Bigg)}\normalsize{} \ (\mbox{from} \ H_{0}^{e}(q))$$Since all joints are rotary:
$$J_{geo}(q) = \large{\Bigg(}\normalsize{}\begin{array}{ccc} z_{DH0}{\times}(s_e{-}s_0) & z_{DH1}{\times}(s_e{-}s_1) & z_{DH2}{\times}(s_e{-}s_2)\\ z_{DH0} & z_{DH1} & z_{DH2} \end{array}\large{\Bigg)}\normalsize{}.$$Making the substitutions:
$$J_{geo}(q) = \Huge{\Bigg(}\normalsize{}\begin{array}{ccc} 0 & 0 & -0{,}2c_3 \\ -(0{,}2c_3+0{,}25)s_{12} {+} 0{,}3s_1 & -(0{,}2c_3+0{,}25)s_{12} & \ 0{,}2s_3c_{12} \\ \ (0{,}2c_3+0{,}25)c_{12} {+} 0{,}3c_1 & \ (0{,}2c_3+0{,}25)c_{12} & -0{,}2s_3s_{12} \\ 1 & 1 & 0 \\ 0 & 0 & -s_{12}\\ 0 & 0 & \ c_{12} \end{array}\Huge{\Bigg)}\normalsize{}.$$Yes. Without rotary joints, the end-effector never changes its orientation, and therefore \(\omega\) is always the zero vector for all \(q\) and \(\dot{q}\). This implies \(J_{\omega}(q)\) being the zero matrix.
Yes. It is possible. Note that \(\omega = J_{\omega}(q)\dot{q}\). Differentiating in time and using the product rule:
$$\alpha = \left(\frac{d}{dt}J_{\omega}(q)\right)\dot{q} + J_{\omega}(q)\ddot{q}.$$By the chain rule, since \(J_{\omega}(q)\) depends only on \(q\), the time derivative will depend on \(q\) and \(\dot{q}\) (but not on \(\ddot{q}\)). In any case, the first term of this derivative will be a non-linear function of \(q, \dot{q}\), and therefore:
$$\alpha = f(q,\dot{q}) + J_{\omega}(q)\ddot{q}.$$If \(\ddot{q}=0\), the second term vanishes, but the first does not necessarily. Therefore, it is still possible to have a non-zero angular acceleration.
Yes. Note that if \(J_{geo}(q)\dot{q}_1 = \xi_{d1}\) and \(J_{geo}(q)\dot{q}_2 = \xi_{d2}\), adding these two equalities:
$$J_{geo}(q)(\dot{q}_1+\dot{q}_2) = \xi_{d1}+\xi_{d2}=\xi_{d3}.$$The last equation suggests that it is enough to choose \(\dot{q}_3 = \dot{q}_1+\dot{q}_2\).
To be more general, remember that in Class 4 it was said that the space of achievable velocities is a vector space. So, if \(\xi_{d1}\) and \(\xi_{d2}\) are achievable, any linear combination of them is also achievable.
The configuration is not singular. Here is the code:
import uaibot as ub
import numpy as np
robot = ub.Robot.create_staubli_tx60()
#Calculate the geometric Jacobian in the configuration
jg, _ = robot.jac_geo(q=[0,1.57,0.1,0.1,0.1,0])
#Calculate the singular values
sq_sing_values, _ = np.linalg.eig(jg.T * jg)
sing_values = np.sqrt(sq_sing_values)
#Print the singular values, the smallest is 0.02!
print(sing_values)
#Calculate what the configuration velocity should be:
xi_d = np.matrix([0,0,1,0,0,0]).reshape((6,1))
#I can use the inverse because the matrix is non-singular and square
qdot = np.linalg.inv(jg) * xi_d
#Print the joint velocity
print(qdot)
In this situation, we have \(v_d = (0 \ 0{,}6 \ 0)^T\) and \(\omega_d = (0 \ 0 \ 1)^T\).
This is very coherent. When the first joint rotates clockwise, the end-effector will have a velocity in the \(y_0\) axis of the world. Also, since the distance from the joint to the end-effector is \(0{,}6 m\), the linear velocity is \(1 \times 0,6 m/s\). See the image on the side.
The angular velocity of the end-effector will have only a component in \(z_0\), being equal to the joint velocity, \(1 rad/s\).
import uaibot as ub
import numpy as np
robot = ub.Robot.create_epson_t6(color="gray")
jg, _ = robot.jac_geo()
qdot = np.matrix([1,0,0]).reshape((3,1))
print(jg * qdot)
Let's use the example from Class 3 as a basis:
import numpy as np
import uaibot as ub
robot = ub.Robot.create_kuka_kr5()
sim = ub.Simulation([robot])
#Let's create a target HTM for the end-effector that is the same as the initial one, but shifted
#a bit downwards
target = ub.Utils.trn([0,0,-0.3]) * robot.fkm()
#Let's find out what the configuration should be to give this HTM for the end-effector:
q_ikm = robot.ikm(htm_target = target)
#Let's make a smooth animation of the robot going from the initial configuration to
#the target configuration
dt=0.01
tmax = 10
for i in range(round(tmax/dt)):
t = i*dt
q_c = (1-t/tmax) * robot.q0 + (t/tmax) * q_ikm
#We need the geometric Jacobian and forward kinematics to do
#the calculations
jg, fk = robot.jac_geo()
#Calculate omega and print
qdot = (q_ikm-robot.q0)/tmax
omega = jg[3:6,:]*qdot
print("omega("+str(t)+") = "+str(omega.reshape((3,))))
#Calculate the Euler angle
[alpha, beta, gamma] = ub.Utils.euler_angles(fk)
#Store the previous value, if it exists
if i > 0:
phi_ant = phi
phi = np.matrix([gamma,beta,alpha]).reshape((3,1))
#Calculate the derivative of the Euler angles numerically
#and print
if i > 0:
dphi_dt = (phi-phi_ant)/dt
print("dphi_dt("+str(t)+") = "+str(dphi_dt.reshape((3,)))+"\n")
robot.add_ani_frame(time=t, q=q_c)
sim.run()