4

I've taken a class and started a thesis on robotics and my reference for calculating the Jacobian by product of exponentials seems incorrect, see:

http://www.cds.caltech.edu/~murray/books/MLS/pdf/mls94-complete.pdf

Specifically the resulting Jacobian matrix for the SCARA manipulator on page 118 would have us believe that the end effector translational velocity depends on joints 2 and 3 rather than 1 and 2.

Could someone please explain me why?

Drew
  • 95
  • 8

1 Answers1

4

The Jacobian in that equation is from the joint velocity to the "spatial velocity" of the end effector.

The spatial velocity of an object is a somewhat unintuitive concept: it is the velocity of a frame rigidly attached to the end effector but currently coincident with the origin frame. It may help to think of the rigid body as extending to cover the whole space, and you're measuring the velocity by standing at the origin and looking at what is happening to the end effector where you are, instead of at the end of the arm.

In the example given, the origin is at the same location as the first joint. This means that rotating the joint will sweep the end effector in a circle, but that the frame at the origin will only pivot around the vertical axis; this is encoded by the first column of the Jacobian being [0 0 0 0 0 1]'.

Rotating joints two and three will pull the origin-overlapping frame away from the origin, and hence have translational components.

To see how this works in action, note that the Jacobian that you asked about from MLS can be simplified to

$J_{st,SCARA}^{s} = \begin{bmatrix} 0 & \phantom{-}y_{2} & \phantom{-}y_{3} & 0\\ 0 & -x_{2} & - x_{3} & 0 \\ 0 &0&0&1 \\ 0& 0& 0&0\\ 0& 0& 0&0\\ 1&1&1 &0 \end{bmatrix}, $

in which the first three columns encode the velocity at the origin of an object rotating around the corresponding axis and the fourth column gives the velocity at the origin of an object sliding up the fourth axis.

You can convert the spatial-velocity Jacobian into a world-frame Jacobian by incorporating the Jacobian from base-frame motion to motion at the end effector's current position and orientation. For the SCARA arm, this works out fairly cleanly, with the only difference between the two frame velocities being the "cross product" term that accounts for the extra motion of the end effector sweeping around the base,

$ J^{w}_{st, SCARA} = \begin{bmatrix} % \begin{pmatrix} 1 &&\\ &1&\\ && 1 \end{pmatrix} % & % \begin{pmatrix} 0 & & -y_{4}\\ & 0 & \phantom{-}x_{4} \\ & & \phantom{-}0 \end{pmatrix} \\ \begin{pmatrix} 0&& \\ &0&\\ &&0 \end{pmatrix} & \begin{pmatrix} 1 & & \\ & 1 & \\ && 1 \end{pmatrix} \end{bmatrix} J^{s}_{st,\text{SCARA}}. $

This product evaluates to

$ J_{st,SCARA}^{w} = \begin{bmatrix} -y_{4} & -(y_{4}-y_{2}) & -(y_{4}-y_{3}) & 0\\ \phantom{-}x_{4} & \phantom{-}x_{4}-x_{2} & \phantom{-}x_{4}- x_{3} & 0 \\ 0 &0&0&1 \\ 0& 0& 0&0\\ 0& 0& 0&0\\ 1&1&1 &0 \end{bmatrix}, $

which matches what we would expect to see: Each of the rotary joints contributes to the end effector velocity by the cross product between its rotational velocity and the vector from the joint to the end effector (note that $x_{4}-x_{3}$ and $y_{4}-y_{3}$ are both zero).

===

In the general case, where the rotations are not only around the $z$ axis, you would want to use the full form of the matrix mapping between the spatial to world Jacobians,

$ J_{w} = \begin{bmatrix} % \begin{pmatrix} 1 &&\\ &1&\\ && 1 \end{pmatrix} % & % \begin{pmatrix} \phantom{-}0 & \phantom{-}z & -y\\ -z& \phantom{-}0 & \phantom{-}x \\ \phantom{-}y& -x & \phantom{-}0 \end{pmatrix} \\ \begin{pmatrix} 0&& \\ &0&\\ &&0 \end{pmatrix} & \begin{pmatrix} 1 & & \\ & 1 & \\ && 1 \end{pmatrix} \end{bmatrix} J^{s}, $

which encodes the cross product terms for all three rotation axes when the end effector is at $(x,y,z)$ relative to the base frame.

RLH
  • 619
  • 3
  • 5
  • The base velocity of a frame rigidly attached to the end effector, strange. I don't know how i would use that. Might this mean the body jacobian, produces the end effector velocity in a base relative frame? – Drew Jan 28 '16 at 14:52
  • no, I don't know what this is either: Jb =

    [ - l1cos(q2 + q3) - l2cos(q3), -l2*cos(q3), 0, 0] [ l1sin( q2 + q3) + l2sin(q3), l2*sin( q3), 0, 0] [ 0, 0, 0, 1] [ 0, 0, 0, 0] [ 0, 0, 0, 0] [ 1, 1, 1, 0]

    – Drew Jan 28 '16 at 17:03
  • I'm not sure I understand your second comment. For the first comment, the "spatial velocity" is, as I mentioned, a somewhat unintuitive concept. It's mostly used as a way of expressing that all frames rigidly attached to a single object have a single shared velocity, and then measuring that velocity at the origin for lack of a better choice. You can transform the spatial Jacobian into a world-velocity Jacobian at a given end effector position by using a right group action, or into a body-frame Jacobian by using an adjoint-inverse transformation. – RLH Jan 28 '16 at 20:28
  • I was hoping for a way to directly evaluate what might be called the analytical Jacobian. For the SCARA it should be : [ - l2cos(q1 + q2) - l1cos(q1), -l2*cos(q1 + q2), 0, 0] [ - l2sin(q1 + q2) - l1sin(q1), -l2*sin(q1 + q2), 0, 0] [ 0, 0, 0, 1] [ 0, 0, 0, 0] [ 0, 0, 0, 0] [ 1, 1, 1, 0] Unfortunately, stack exchange is butchering the formatting key read this easily. Built with derivatives, this process is very slow. – Drew Jan 28 '16 at 20:38
  • From what I understand, you want the end-effector Jacobian. The easiest way to get that from the spatial Jacobian is to multiply J_st by the right lifted action. MLS unfortunately doesn't have a directly linked explanation of that action, so I will write it in a second comment. – RLH Jan 28 '16 at 20:42
  • Thank you so much for trying RLH, but I am just not getting it. Can you recommend a book or publication that might explain this "right lifted action" in greater detail? – Drew Jan 28 '16 at 22:10
  • The four blocks in the matrix I posted describe how the end effector velocity depends on the end-effector-at-origin velocity: Top left is that all translational components of EEAO velocity transfer to EE. Bottom right is all rotational components transfer. Top right is that the x and y velocities are affected by the distance away from the origin and the z rotational velocity (like in a cross product). Bottom left is that EE rotational velocity isn't affected by EEAO translational velocity. If you haven't done kinematics with cross-products recently, I suggest brushing up on that first. – RLH Jan 28 '16 at 23:21
  • .. Okay, is there a source you would recommend? – Drew Jan 28 '16 at 23:31
  • Engineering dynamics books with sections on rigid-body mechanics should have enough to get you started. They should all be roughly equivalent in their treatment of basic planar rigid bodies (which you should start with), and the cross-product formulas generalize to three dimensions. Once you're familiar with what is physically happening as rigid bodies move, take another look at the formula I gave in the edited answer. – RLH Jan 28 '16 at 23:44
  • Give me a little credit. My attempt at product above did not make sense. I'll go back to the library, but I would challenge you to produce what you would believe the world Jacobian to be and test your solution. – Drew Jan 28 '16 at 23:54
  • Edited to show just the steps answering the question "Is there an error in MLS 118?" – RLH Jan 29 '16 at 23:35
  • interesting, i'm attempting to apply the trig functions of the scara to your math so I can demonstrate their veracity to myself. The translation matrix or right lifted actor seems to resemble the adjoint construction but not quite. I'm still anxious to know where you learned this and why it's not described in MLS. – Drew Feb 02 '16 at 20:24
  • wow, that is powerful. The 8dof mobile manipulator that originally had me stuck on this problem now seems easy. If there's not a book on this you need to write it. – Drew Feb 02 '16 at 22:04
  • Though this seems to work, I have not found a published source for this math. A key piece of my thesis is now built on an internet post by an anonymous author. – Drew Jul 05 '16 at 19:46
  • Apologies for the long delay in reply. I'm not sure of a good published source on this particular aspect worked out at this level of detail; I've been re-deriving a number of aspects of MLS and related works, with the goal of making the material more broadly accessible. I'm planning to work this into my book (most recent version at geometricmechanics.org), and may be able to pull this into a standalone pamphlet/tutorial by the end of the summer. My contact information is at http://research.engr.oregonstate.edu/lram/ – RLH Jul 06 '16 at 20:22
  • Outstanding, I can now acknowledge and reference you. And I'm anxious to read your works. – Drew Jul 07 '16 at 06:11