3

I have an RRR planar robot:

Its forward kinematics transform is:

$$ {}^{0}T_3 = \\ \left[\begin{array}{cccc} \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right) & - \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right) & 0 & \mathrm{l_2}\, \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2}\right) + \mathrm{l_1}\, \cos\!\left(\mathrm{\theta_1}\right) + \mathrm{l_3}\, \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right)\\ \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right) & \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right) & 0 & \mathrm{l_2}\, \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2}\right) + \mathrm{l_1}\, \sin\!\left(\mathrm{\theta_1}\right) + \mathrm{l_3}\, \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right)\\ 0 & 0 & 1 & 0\\ 0 & 0 & 0 & 1 \end{array}\right] $$

With the joint parameters $q = \left[\begin{array}{ccc} \mathrm{\theta_1} & \mathrm{\theta_2} & \mathrm{\theta_3} \end{array}\right]^T$ and the end-effector position $X = \left[\begin{array}{ccc} \mathrm{x} & \mathrm{y} & \mathrm{\theta} \end{array}\right]^T$. $\theta$ is constrained to 0. (Also the image is misleading, $\theta$ is actually $\theta_1 + \theta_2 + \theta_3$.)

The jacobian matrix is

$$ J = \\ \left[\begin{array}{ccc} - \mathrm{l_2}\, \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2}\right) - \mathrm{l_1}\, \sin\!\left(\mathrm{\theta_1}\right) - \mathrm{l_3}\, \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right) & - \mathrm{l_2}\, \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2}\right) - \mathrm{l_3}\, \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right) & - \mathrm{l_3}\, \sin\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right)\\ \mathrm{l_2}\, \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2}\right) + \mathrm{l_1}\, \cos\!\left(\mathrm{\theta_1}\right) + \mathrm{l_3}\, \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right) & \mathrm{l_2}\, \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2}\right) + \mathrm{l_3}\, \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right) & \mathrm{l_3}\, \cos\!\left(\mathrm{\theta_1} + \mathrm{\theta_2} + \mathrm{\theta_3}\right)\\ 1 & 1 & 1 \end{array}\right] $$

I'm trying to find $\ddot{q}$:

$$ [\ddot{q}] = J^{-1}(q) \cdot \left([\ddot{X}] - \dot{J}(q) \cdot J^{-1}(q) \cdot [\dot{X}] \right) $$

My question is: how can I find $\dot{J}$? What is it?

christophebedard
  • 287
  • 1
  • 3
  • 6

2 Answers2

2

Look at example 283 and its derivation here. You just take the time derivative of each element of J, paying particular attention to the chain rule.

SteveO
  • 4,386
  • 1
  • 10
  • 13
2

You can use Matlab to compute $\dot{J}$. For example, to compute $\dot{J}_{11}$, we can use the following code

clear all
clc
syms T1 T2 T3 l1 l2 l3 t

T1(t) = symfun(sym('T1(t)'), t);
T2(t) = symfun(sym('T2(t)'), t);
T3(t) = symfun(sym('T3(t)'), t);

J11 = -l2*sin(T1(t)+T2(t)) - l1*sin(T1(t)) -l3*sin(T1(t)+T2(t)+T3(t));

dJ11dt = diff(J11,t)

which yields

- l3*cos(T1(t) + T2(t) + T3(t))*(diff(T1(t), t) + diff(T2(t), t) + diff(T3(t), t)) - l1*cos(T1(t))*diff(T1(t), t) - l2*cos(T1(t) + T2(t))*(diff(T1(t), t) + diff(T2(t), t))

Or

$$ \dot{J}_{11} = -l_3\cos(\theta_1 + \theta_2 + \theta_3)(\dot{\theta}_1+\dot{\theta}_2+\dot{\theta}_3) - l_1\cos(\theta_1) \dot{\theta}_1 - l_2\cos(\theta_1+\theta_2)(\dot{\theta}_1+\dot{\theta}_2) $$

Now it is easy to compute the rest.

CroCo
  • 2,453
  • 1
  • 17
  • 40