Robotics 1

Position and orientation of rigid bodies

Prof. Alessandro De Luca

Robotics 1 1 Position and orientation

right-handed orthogonal RFB

Reference Frames A 3 • position: pAB (vector ! R ), B expressed in RF (use of coordinates I A RFA other than Cartesian is possible, e.g. pAB cylindrical or spherical) • orientation: orthonormal 3x3 matrix T -1 A B A (R = R " RB RA = I), with det = +1

A A A A RB = [ xB yB zB]

• xA yA zA (xB yB zB) are unit vectors (with unitary norm) of frame RFA (RFB) A • components in RB are the direction cosines of the axes of RFB with respect to (w.r.t.) RFA Robotics 1 2 matrix

T T T direction cosine of xA xB xA yB xA zB zB w.r.t. xA AR = y T x y T y y T z orthonormal, B A B A B A B T T T with det = +1 zA xB zA yB zA zB algebraic structure chain rule property of a SO(3) (neutral element = I; k i k inverse element = RT) Ri ! Rj = Rj orientation of RFi orientation of RFj w.r.t. RFk w.r.t. RFk orientation of RFj w.r.t. RFi

NOTE: in general, the product of rotation matrices does not commute!

Robotics 1 3 Change of coordinates

z0 0 px 0P = 0p = 1p 0x + 1p 0y + 1p 0z z1 • P y x 1 y 1 z 1 0p z 1 px y 1 0 0 0 1 = x1 y1 z1 py 1 pz RF1 y0 = 0R 1P RF0 1

x0 0 the R1 (i.e., the orientation of RF1 w.r.t. RF0) represents also the change of x1 coordinates of a vector from RF1 to RF0

Robotics 1 4 Ex: Orientation of frames in a (elementary rotation around z-axis)

x = OB – xB = u cos # - v sin #$ y P • y = OC + Cy = u sin # + v cos #$ RFC z = w v # or… C u C 0 0 0 OP # RF0 xC yC zC O x B x cos # $-sin # $0 u u 0 OP y = sin # $ cos # 0 v = Rz(#) v z 0 0 1 w w

R (-#) = R T(#) similarly: z z

1 0 0 cos # 0 sin # Rx(#) = 0 cos # - sin # Ry(#) = 0 1 0

0 sin # cos #$ - sin # 0 cos #$

Robotics 1 5 Ex: Rotation of a vector around z

v’ x = |v| cos %$ y’ y = |v| sin %$ v y x’ = |v| cos (% + #) = |v| (cos % cos # - sin % sin #) # x’ = x cos # - y sin # %$ y’ = |v| sin (% + #) = |v| (sin % cos # + cos % sin #) x’ x O x’ = x sin # + y cos #

z’ = z or…

x’ cos # - sin # 0 x x …as y’ = sin # cos # 0 y = Rz(#) y before! z’ 0 0 1 z z

Robotics 1 6 Equivalent interpretations of a rotation matrix

the same rotation matrix, e.g., Rz(#), may represent: v’ RF C v • P RFC # # # RF RF0 0

the orientation of a rigid the change of coordinates the vector

body with respect to a from RFC to RF0 rotation operator 0 C reference frame RF0 ex: P = Rz(#) P ex: v’ = Rz(#) v 0 0 0 ex: [ xc yc zc] = Rz(#)

0 the rotation matrix RC is an operator superposing frame RF0 to frame RFC Robotics 1 7 Composition of

1 brings RF on RF 2 brings RF on RF brings RF0 on RF1 R2 1 2 R3 2 3

0 R1

• 3p p23 = 0 p = 0 01 p12 = 0 RF2 RF3 RF1 RF 0 a comment on computational complexity 63 products 0p = (0R 1R 2R ) 3p = 0R 3p 1 2 3 3 42 summations

0 0 1 2 3 27 products p = R1 ( R2 ( R3 p)) 18 summations 2p 1 Robotics 1 p 8 Axis/ representation

z 0 DATA r z • r (!r! = 1)$ r (positive if counterclockwise, as • P • # v seen from an “observer” placed like r) z1 y1 #$ DIRECT PROBLEM RF1 v’ ry find y0 RF0 0 0 0 R(#,r) = [ x1 y1 z1] rx RF is the result of rotating such that x0 1 RF by an angle around 0 # 0 1 0 0 the unit vector r P= R(#,r) P v’ = R(#,r) v

x1

Robotics 1 9 Axis/angle: Direct problem

z T 0 R(#,r) = C Rz(#) C 1 C concatenation of three rotations C-1 = CT r 3 C = n s r 2 z1 y1 Rz(#)

RF1 after the first rotation y0 the z-axis coincides with r RF0 sequence of 3 rotations that n and s are orthogonal x 0 bring frame RF0 to superpose unit vectors such that with frame RF1 n " s = r, or

nysz - synz = rx x1 nzsx - sznx = ry

nxsy - sxny = rz Robotics 1 10 Axis/angle: Direct problem solution

T R(#,r) = C Rz(#) C

T c# - s# 0 n T R(#,r) = n s r s# c# 0 s 0 0 1 rT

T T T T T = r r + (n n + s s ) c# + (s n - n s ) s# taking into account that T T T T C C = n n + s s + r r = I , and that 0 -r r z y skew-symmetric(r): T T s n - n s = 0 -r = S(r) x r " v = S(r)v = - S(v)r 0 depends only T T T R(#,r) = r r + (I - r r ) c# + S(r) s# = R (-#,r) = R(-#,-r) on r and # !!

Robotics 1 11 Rodriguez formula

v’ = R(#,r) v

v’ = v cos # + (r " v) sin # + (1 - cos #)(rTv) r

proof:

T T R(#,r) v = (r r + (I - r r ) cos # + S(r) sin #)v

T = r r v (1 - cos #) + v cos # + (r " v) sin # q.e.d.

Robotics 1 14 Unit quaternion

" to eliminate undetermined and singular cases arising in the axis/angle representation, one can use the unit quaternion representation Q = {-, .} = {cos(#/2), sin(#/2) r} a scalar 3-dim vector 2 2 " - + !.! = 1 (thus, “unit ...”) " (#, r) and (-#, -r) gives the same quaternion Q " the absence of rotation is associated to Q = {1, 0} " unit quaternions can be composed with special rules (in a similar way as in the product of rotation matrices)

T Q 1*Q 2 = {-1-2 - .1 .2, -1.2 + -2.1 + .1".2}

Robotics 1 20 Robotics 1

Minimal representations of orientation (Euler and roll-pitch-yaw ) Homogeneous transformations

Prof. Alessandro De Luca

Robotics 1 1 “Minimal” representations

 rotation matrices: 9 elements inverse problem - 3 orthogonality relationships - 3 unitary relationships = 3 independent variables direct problem problem direct

 sequence of 3 rotations around independent axes

 fixed (ai) or moving/current (a’i) axes

 12 + 12 possible different sequences (e.g., XYX)

 actually, only 12 since

{(a1 α1), (a2 α2), (a3 α3)} ≡ { (a’3 α3) , (a’2 α2), (a’1 α1)}

Robotics 1 2 ZX’Z’’

1 z≡z’ z’ z’’ 2 y’’ RF” φ y’ RF’ θ y’ R (θ) = RF x’ θ 1 0 0 y 0 cos θ -sin θ x φ x’ x’≡x’’ 0 sin θ cos θ cos φ - sin φ 0 z’’ z’’’ Rz(φ) = sin φ cos φ 0 ≡ 3 y’’’ 0 0 1 y’’ ψ RF”’ cos ψ - sin ψ 0

R ( ) = z” ψ sin ψ cos ψ 0 x’’ x’’’ 0 0 1 ψ Robotics 1 3 ZX’Z’’ Euler angles

 direct problem: given φ , θ , ψ ; find R

RZX’Z’’ (φ, θ, ψ) = RZ (φ) RX’ (θ) RZ’’ (ψ) order of definition cφ cψ - sφ cθ sψ - cφ sψ - sφ cθ cψ sφ sθ in concatenation = sφ cψ + cφ cθ sψ - sφ sψ + cφ cθ cψ - cφ sθ sθ sψ sθ cψ cθ

 given a vector v”’= (x”’,y”’,z”’) expressed in RF”’, its expression in the coordinates of RF is

v = RZX’Z’’ (φ, θ, ψ) v”’

 the orientation of RF”’ is the same that would be obtained with the sequence of rotations: ψ around z, θ around x (fixed), φ around z (fixed)

Robotics 1 4 Roll-Pitch-Yaw angles

ROLL PITCH 1 z’ 2 z z’’ z’ y’’ ψ T y’ C1RY(θ)C1 y’ θ with RY(θ) =

θ y cos θ 0 sin θ y 0 1 0 x’ ψ x’’ - sin θ 0 cos θ x≡x’ YAW z 3 y’’’ 1 0 0 z’’ φ y’’ RX(ψ) = 0 cos ψ - sin ψ 0 sin ψ cos ψ

T z’’’ C2RZ(φ)C2 cos φ - sin φ 0

with RZ(φ) = sin φ cos φ 0 0 0 1 x’’ φ x’’’ Robotics 1 6 Roll-Pitch-Yaw angles (fixed XYZ)

 direct problem: given ψ , θ , φ ; find R

⇐ note the order of products! RRPY (ψ, θ, φ) = RZ (φ) RY (θ) RX (ψ) order of definition cφ cθ cφ sθ sψ - sφ cψ cφ sθ cψ + sφ sψ = sφ cθ sφ sθ sψ + cφ cψ sφ sθ cψ - cφ sψ - sθ cθ sψ cθ cψ

 inverse problem: given R = {rij}; find ψ , θ , φ

2 2 2 2 2  r32 + r33 = c θ, r31 = -sθ ⇒ θ = ATAN2{-r31, ± √ r32 + r33 } 2 2 two symmetric values w.r.t. π/2  if r32 + r33 ≠ 0 (i.e., cθ ≠ 0)

r32/cθ = sψ, r33/cθ = cψ ⇒ ψ = ATAN2{r32/cθ, r33/cθ}

 similarly... φ = ATAN2{ r21/cθ, r11/cθ }  singularities for θ = ± π/2

Robotics 1 7 Homogeneous transformations

P • Bp RF Ap B A ‘affine’ relationship pAB OB RFA A A A B p = pAB + RB p OA

A A A B p RB pAB p linear A A B phom = = = TB phom relationship 1 0 0 0 1 1

vector in homogeneous 4x4 matrix of coordinates homogeneous transformation Robotics 1 9 Properties of T matrix

 describes the relation between reference frames (relative pose = position & orientation)

 transforms the representation of a position vector (applied vector from the origin of the frame) from a given frame to another frame

 it is a roto- operator on vectors in the three-dimensional A -1 B  it is always invertible ( TB) = TA A A B  can be composed, i.e., TC = TB TC ← note: it does not commute!

Robotics 1 10 Inverse of a homogeneous transformation

A A A B B B B A A T A A T A p = pAB + RB p p = pBA + RA p = - RB pAB + RB p

A A B B A T A T A RB pAB RA pBA RB - RB pAB =

0 0 0 1 0 0 0 1 0 0 0 1

A B A -1 TB TA ( TB)

Robotics 1 11 Defining a robot task

yE absolute definition of task task definition relative RFE to the robot end-effector zE RFB W W B E 2 • TT = TB TE TT 1 • RFT •3 known, once the robot direct of the is placed robot arm (function of q)

RFW

B W -1 W E -1 TE(q) = TB TT TT = cost

Robotics 1 12 Final comments on T matrices

 they are the main tool for computing the direct kinematics of robot manipulators

 they are used in many application areas (in robotics and beyond) b  in the positioning of a vision camera (matrix Tc with the extrinsic parameters of the camera posture)

 in computer graphics, for the real-time visualization of 3D solid objects when changing the observation point

A A RB pAB A TB = αx αy αz σ

all zero coefficients of scaling always unitary in robotics perspective coefficient in robotics deformation Robotics 1 13 Robotics 1

Direct kinematics

Prof. Alessandro De Luca

Robotics 1 1 Kinematics of robot manipulators

! “study of geometric and time properties of the of robotic structures, without reference to the causes producing it”

! robot seen as “(open) kinematic chain of rigid bodies interconnected by (revolute or prismatic) joints”

Robotics 1 2 Motivations

! functional aspects

! definition of robot workspace

! calibration ! operational aspects task execution task definition and (actuation by motors) performance two different “” related by kinematic (and dynamic) maps

! trajectory planning

! programming

! motion control

Robotics 1 3 Kinematics formulation and parameterizations r = f(q) TASK JOINT DIRECT (Cartesian) space INVERSE space

-1 q = (q1,…,qn) q = f (r) r = (r1,…,rm)

! choice of parameterization q

! unambiguous and minimal characterization of the robot configuration

! n = # degrees of freedom (dof) = # robot joints (rotational or translational) ! choice of parameterization r

! compact description of positional and/or orientation (pose) components of interest to the required task ! m ! 6, and usually m ! n (but this is not strictly needed)

Robotics 1 4 Open kinematic chains

RF q2 qn E q4 q 1 q3 r = (r1,…,rm)

e.g., the relative angle e.g., it describes the between a link and the pose of frame RFE following one

! m = 2

! pointing in space

! positioning in the plane

! m = 3

! orientation in space

! positioning and orientation in the plane

Robotics 1 5 Classification by kinematic type (first 3 dofs)

SCARA (RRP)

cylindric cartesian or (RPP) gantry (PPP) articulated or anthropomorphic (RRR) polar or spherical (RRP)

P = 1-dof translational (prismatic) joint R = 1-dof rotational (revolute) joint Robotics 1 6 Direct kinematic map

! the structure of the direct kinematics function depends from the chosen r

r = fr(q)

! methods for computing fr(q) ! geometric/by inspection

! systematic: assigning frames attached to the robot links and using homogeneous transformation matrices

Robotics 1 7 Example: direct kinematics of 2R arm y q P " q = 1 n = 2 py • q2 l2 q2 l px 1 r = p m = 3 q y 1 " px x

px = l1 cos q1 + l2 cos(q1+q2)

py = l1 sin q1 + l2 sin(q1+q2)

" = q1+ q2 for more general cases we need a “method”! Robotics 1 8 Numbering links and joints

joint 2 joint i+1 link i-1 joint n link 1 link n joint 1 link i joint i-1 link 0 joint i (base) (end effector)

revolute prismatic

Robotics 1 9 Relation between joint axes

axis of joint i axis of joint i+1 90° % $

A # i$

90°

common B (axis of link i)

a i = distance AB between joint axes (always well defined) with sign # i = twist angle between joint axes (pos/neg)! [projected on a plane % orthogonal to the link axis]

Robotics 1 10 Relation between link axes

axis of joint i link i-1

link i D

C axis of link i-1 axis of link i ' $ &i

d i = distance CD (a variable if joint i is prismatic) with sign & i = angle (a variable if joint i is revolute) between link axes (pos/neg)! [projected on a plane ' orthogonal to the joint axis] Robotics 1 11 Frame assignment by Denavit-Hartenberg (DH)

joint axis joint axis joint axis i-1 i i+1 link i-1 link i

frame RFi is attached to link i #i zi ai z di i-1 O xi-1 i xi &i O i-1 common normal to joint axes axis around which the link rotates i and i+1 or along which the link slides

Robotics 1 12 Denavit-Hartenberg parameters

axis of joint axis of joint axis of joint i-1 i link i i+1 link i-1 #i D zi • ai d zi-1 i O xi-1 i xi &i Oi-1

! unit vector zi along axis of joint i+1

! unit vector xi along the common normal to joint i and i+1 axes (i ( i+1)

! ai = distance DOi – positive if oriented as xi (constant = “length” of link i)

! di = distance Oi-1D – positive if oriented as zi-1 (variable if joint i is PRISMATIC)

! #i = twist angle between zi-1 and zi around xi (constant) ! &i = angle between xi-1 and xi around zi-i (variable if joint i is REVOLUTE)

Robotics 1 13 Homogeneous transformation

between DH frames (from framei-1 to framei)

! roto-translation around and along zi-1

c&i -s&i 0 0 1 0 0 0 c&i -s&i 0 0 0 1 0 0 i-1 s&i c&i 0 0 s&i c&i 0 0 Ai’ (qi) = = 0 0 1 0 0 0 1 di 0 0 1 di 0 0 0 1 0 0 0 1 0 0 0 1

rotational joint ) qi = &i prismatic joint ) qi = di

! roto-translation around and along xi

1 0 0 ai 0 c -s 0 i’ #i #i always a Ai = 0 s#i c#i 0 constant matrix 0 0 0 1 Robotics 1 15 Denavit-Hartenberg matrix

c&i -c#i s&i s#i s&i aic&i

s& c# c& -s# c& a s& i-1 i-1 i’ i i i i i i i Ai (qi) = Ai’ (qi) Ai = 0 s#i c#i di

0 0 0 1

compact notation: c = cos, s = sin

Robotics 1 16 Direct kinematics of manipulators description “internal” yE slide s to the robot using: 0 1 n-1 zE approach a • product A1(q1) A2(q2)… An(qn) • q=(q ,…,q ) 1 n xE normal n z0

y0 RF B “external” description using • r = (r ,…,r ) x0 1 m

B R p n s a p B B 0 1 n-1 n • TE= = TE = T0 A1(q1) A2(q2) … An(qn) TE 000 1 0 0 0 1

r = fr(q)

Robotics 1 alternative descriptions of robot direct kinematics 17 Example: SCARA robot

q3

q2

q1 q4

Robotics 1 18 Step 1: joint axes

all parallel (or coincident)

twists # i = 0 or % J3 prismatic ≡ J1 shoulder J4 revolute J2 elbow

Robotics 1 19 Step 2: link axes

the vertical “heights” of the link axes are arbitrary (for the time being) a 2 a3 = 0 a1

Robotics 1 20 Step 3: frames

z1

x z2 = z3 yi axes for i > 0 1 are not shown (and not needed; x2 they form x right-handed frames) 3 x4

z4 = a axis z0 (approach)

y0 x0

Robotics 1 21 Step 4: DH parameters table

i # i$ ai di & i

z1 1 0 a1 d1 q1 z2 = z3 x1 2 0 a2 0 q2

x2 3 0 0 q3 0 x3 x4 4 % 0 d4 q4

z4 z0

y 0 note: d1 and d4 could have been chosen = 0 ! x0 moreover, here it is d4 < 0 !!

Robotics 1 22 Step 5: transformation matrices

c&1 - s&1 0 a1c&1 0 s&1 c&1 0 a1s&1 A1(q1)= 0 0 1 d1 0 0 0 1 1 0 0 0 c&2 - s&2 0 a2c&2 0 1 0 0 2A (q )= 1 s&2 c&2 0 a2s&2 3 3 A2(q2)= 0 0 1 d3 0 0 1 0 0 0 0 1 0 0 0 1

c&4 s&4 0 0 3 s&4 -c&4 0 0 q = (q1, q2, q3, q4) A4(q4)= 0 0 -1 d4 = (&1, &2, d3, &4) 0 0 0 1

Robotics 1 23 Step 6: direct kinematics

c12 -s12 0 a1c1+ a2c12 0 s12 c12 0 a1s1+ a2s12 A3(q1,q2,q3)= 0 0 1 d1+q3 0 0 0 1

c4 s4 0 0 3 s4 -c4 0 0 A4(q4)= 0 0 -1 d4 0 0 0 1

R(q ,q ,q )=[ n s a ] 1 2 4 c124 s124 0 a1c1+ a2c12 0 s124 -c124 0 a1s1+ a2s12 p = p(q1,q2,q3) A4(q1,q2,q3,q4)= 0 0 -1 d1+q3+d4 0 0 0 1 Robotics 1 24 Robotics 1

Differential kinematics

Prof. Alessandro De Luca

Robotics 1 1 Differential kinematics

 “relationship between motion (velocity) in the joint space and motion (linear and angular velocity) in the task (Cartesian) space”

 instantaneous velocity mappings can be obtained through time derivation of the direct kinematics function or geometrically at the differential level

 different treatments arise for rotational quantities

 establish the link between angular velocity and

 time derivative of a rotation matrix

 time derivative of the angles in a minimal representation of orientation

Robotics 1 2 Linear and angular velocity of the robot end-effector

. . ω θ v ω2 = z1θ2 ωn = zn-1 n . ω1 = z0θ1 . v = z d . 3 2 3 = z θ ωi i-1 i r = (p,φ) alternative definitions R p of the e-e direct kinematics T = 000 1

 v and ω are “vectors”, namely elements of vector spaces: they can be obtained as the sum of contributions of the joint velocities (in any order)  on the other hand, φ (and dφ/dt) is not an element of a vector space: a minimal representation of a sequence of rotations is not obtained by summing the corresponding minimal representations (angles φ) in general, ω ≠ dφ/dt Robotics 1 4 Finite and infinitesimal translations

 finiteΔx, Δy, Δz or infinitesimal dx, dy, dz translations (linear displacements) always commute

Δ z Δy z z

y = y x x Δz Δy same final position

Robotics 1 5 Finite rotations do not commute example z z

initial φ X = 90° orientation y y

x x mathematical fact: ω is NOT an exact differential form z φ Z = 90° z (the integral of ω over time depends on the integration path!)

φ = 90° y Z z y x x φ X = 90° different final orientations y x note: finite rotations still commute when Robotics 1 made around the same fixed axis 6 Infinitesimal rotations commute!

 infinitesimal rotations dφX, dφY, dφZ around x,y,z axes 1 0 0 1 0 0 R (dφ ) = 0 1 -d RX(φX) = 0 cos φX -sin φX X X φX

0 d 1 0 sin φX cos φX φX

1 0 d cos φY 0 sin φY φ Y R (d ) = RY(φY) = 0 1 0 Y φY 0 1 0 -d 0 1 -sin φY 0 cos φY φ Y

1 -dφ 0 cos φZ -sin φZ 0 Z R ( ) = RZ(dφZ) = dφ 1 0 Z φZ sin φZ cos φZ 0 Z 0 0 1 0 0 1 neglecting 1 -dφz dφY second- and third-order  R(dφ) = R(dφ , dφ , dφ ) = dφz 1 -dφX X Y Z (infinitesimal) - dφY dφX 1 terms in any sequence Robotics 1 = I + S(dφ) 7 Time derivative of a rotation matrix

. let R = R(t) be a rotation matrix, given as a function of time . since I = R(t)RT(t), taking the time derivative of both sides yields 0 = d[R(t)RT(t)]/dt = dR(t)/dt RT(t) + R(t) dRT(t)/dt = dR(t)/dt RT(t) + [dR(t)/dt RT(t)]T thus dR(t)/dt RT(t) = S(t) is a skew-symmetric matrix

. let p(t) = R(t)p’ a vector (with constant norm) rotated over time . comparing ω dp(t)/dt = dR(t)/dt p’ = S(t)R(t) p’ = S(t) p(t) dp(t)/dt = ω(t) × p(t) = S(ω(t)) p(t) p . we get S = S(ω) p . . R = S(ω) R S(ω) = R RT

Robotics 1 8 Robot Jacobian matrices

 analytical Jacobian (obtained by time differentiation)

. . p p ∂fr(q) . r = = fr(q) r = . = q = Jr(q) q φ φ ∂q

 geometric Jacobian (no derivatives)

. v p J (q) . . = = L q = J(q) q ω ω JA(q)

Robotics 1 11 Geometric Jacobian

always a 6 x n matrix end-effector . . … q1 v J (q) J (q) J (q) … instantaneous E = L q = L1 Ln … . velocity ωE JA(q) JA1(q) JAn(q) qn

superposition of effects . . . . vE = JL1(q) q1 +…+ JLn(q) qn ωE = JA1(q) q1 +…+ JAn(q) qn

contribution to the linear . contribution to the angular. e-e velocity due to q1 e-e velocity due to q1

linear and angular velocity belong to (linear) vector spaces in R3

Robotics 1 14 Contribution of a prismatic joint

Note: joints beyond the i-th one are considered to be “frozen”, . . so that the distal part of the robot is a single rigid body JLi(q) qi = zi-1 di

zi-1 E

prismatic i-th joint . . JLi(q) qi zi-1 di qi = di . JAi(q) qi 0 RF0

Robotics 1 15 Contribution of a revolute joint

. JLi(q) qi . . JAi(q) qi = zi-1 θi

zi-1

p Oi-1 • i-1,E

revolute qi = θi i-th joint . . JLi(q) qi (zi-1 × pi-1,E) θi RF 0 . . JAi(q) qi zi-1 θi

Robotics 1 16 Expression of geometric Jacobian

. . . … q1 p v J (q) J (q) J (q) … ( 0,E =) E = L q = L1 Ln … . ωE ωE JA(q) JA1(q) JAn(q) qn

prismatic revolute this can be also i-th joint i-th joint computed as

∂p0,E JLi(q) zi-1 zi-1 × pi-1,E = ∂qi

JAi(q) 0 zi-1

0 0 i-2 all vectors should be zi-1 = R1(q1)… Ri-1(qi-1) 0 1 expressed in the same reference frame pi-1,E = p0,E(q1,…,qn) - p0,i-1(q1,…,qi-1) (here, the base frame RF0)

Robotics 1 17 Robot Jacobian decomposition in linear subspaces and duality

space of space of joint velocities J task (Cartesian) velocities

0 0 ℵ(J) (J) ℜ dual spaces

ℜ(JT) + ℵ(J) = Rn ℜ(J) + ℵ(JT) = Rm dual spaces T ℜ(J ) ℵ(JT) 0 0

space of space of task (Cartesian) joint T J

Robotics 1 (in a given configuration q) 26 Mobility analysis

T T  ρ(J) = ρ(J(q)), ℜ(J) = ℜ(J(q)), ℵ(J )= ℵ(J (q)) are locally defined, i.e., they depend on the current configuration q

 ℜ(J(q)) = subspace of all “generalized” velocities (with linear and/or angular components) that can be instantaneously realized by the robot end-effector when varying the joint velocities in the configuration q

 if J(q) has max rank (typically = m) in the configuration q, the robot end-effector can be moved in any direction of the task space Rm m  if ρ(J(q)) < m, there exist directions in R along which the robot end- effector cannot instantaneously move T  these directions lie in ℵ(J (q)), namely the complement of ℜ(J(q)) to the task space Rm, which is of dimension m - ρ(J(q))  when ℵ(J(q)) ≠ {0} (this is always the case if m

Robotics 1 27 Kinematic singularities

 configurations where the Jacobian loses rank ⇔ loss of instantaneous mobility of the robot end-effector  for m=n, they correspond in general to Cartesian poses that lead to a number of inverse kinematic solutions that differs from the “generic” case

 “in” a singular configuration, one cannot find a joint velocity that realizes a desired end-effector velocity in an arbitrary direction of the task space

 “close” to a singularity, large joint velocities may be needed to realize some (even small) velocity of the end-effector

 finding and analyzing in advance all singularities of a robot helps in avoiding them during trajectory planning and motion control

 when m = n: find the configurations q such that det J(q) = 0

 when m < n: find the configurations q such that all m×m minors of J are singular (or, equivalently, such that det [J(q) JT(q)] = 0)  finding all singular configurations of a robot with a large number of joints, or the actual “distance” from a singularity, is a hard computational task

Robotics 1 28