<<

2. MANIPULATOR KINEMATICS

Position vectors and their transformations Direct and inverse kinematics of manipulators Transformation of velocity and torque vectors Classification of kinematical chains of manipulator Cartesian, polar cylindrical and spherical and angular coordinates of manipulators Multilink manipulators and manipulators with flexible links Manipulators with parallel kinematics Kinematics of mobile

2.1. Position vectors and their transformation

Manipulator kinematics is the field of science that investigates the motion of manipulator links without regard to the forces that cause it. In that case the motion is determined with trajectory, i.e. positions, velocity, acceleration, jerk and other higher derivative components.

r The location of a point A in Cartesian coordinates {A} is determined by vector AP (Fig 2.1), the individual element of which are projections to the three orthogonal axes of coordinates x, y, z, respectively. The projections px, py and pz can be considered as three orthogonal vectors.

⎡ px ⎤ r AP = ⎢ p ⎥. (2.1) ⎢ y ⎥ ⎣⎢ pz ⎦⎥

The orientation of a body in Cartesian space {A} is determined by three unit vectors r r r ,, zyx BBB that are attached to the body. These orthogonal unit vectors form the Cartesian coordinate system {B} that can be called body coordinates {B}. Therefore, the orientation of a body in space coordinates can be described by the rotation of body coordinates {B} relative r to the reference coordinates {A}. The unit vector xB can be described in Cartesian space coordinates {A} with three projections to coordinate axes xA, yA, zA. In the same way, other r r unit vectors yB and zB can be described.

{A} z

pz

AP

OA y

py px

x

Figure 2.1. Position vector of a point in Cartesian coordinates

32 Generally

X X X ⎡ xB ⎤ ⎡ yB ⎤ ⎡ zB⎤ A r ⎢ Y ⎥ A r ⎢ Y ⎥ A r ⎢ Y ⎥. (2.2) X B = ⎢ xB ⎥ YB = ⎢ yB ⎥ ZB = ⎢ zB ⎥ ⎢ Z ⎥ ⎢ Z ⎥ ⎢ Z ⎥ ⎣ xB ⎦ ⎣ yB ⎦ ⎣ zB ⎦

A r A r A r A Three vectors: X B , YB and ZB will form the rotation matrix B R, which describes the orientation of coordinates {B} relative to coordinates {A}.

X X X ⎡ B B zyx B ⎤ A ⎢ Y Y Y ⎥ A A A rrr B R = ⎢ B B zyx B ⎥ = [B B ZYX B ].,, (2.3) ⎢ Z Z Z ⎥ ⎣ B B zyx B ⎦

The position of coordinates {B} relative to coordinates {A} (Fig. 2.2) is defined by the A r position vector PBO of the origin of coordinates {B} in coordinates {A} and rotation matrix A B R.

AA r {}= {B PR BO }.,B (2.4)

r The position vector B P in translated coordinates {B} relative to coordinates {A} (Fig. 2.3) is defined by the sum of two vectors

ABA rrr += PPP BO . (2.5)

r The position vector B P in rotated coordinates {B} relative to coordinates {A} is defined A A r by the rotation matrix B R . In this case the position vector P is determined as the scalar A B r product of the rotation matrix B R and the position vector P (2.6).

{A} zA {B} xB

OB yB

A zB PBO OA

yA

xA

Figure 2.2 Determination of manipulator gripper or tool orientation

33

{Β} zB {Α} zA BP

A A P PBO OB yB

xB

OA

yA

x A

Figure 2.3 Position vectors in translated coordinates {A} and {B}

A BA rr B ⋅= PRP . (2.6)

A The rotation matrix B R describes the rotation of coordinates {B} relative to coordinates {A}. We can use the rotation matrix to describe inversely coordinates {A} relative to coordinates B {B}. This transformation will be described by the rotation matrix A R . It is known from the course of linear algebra that the inverse of matrix with orthonormal columns is equal to its transpose. The transpose of the matrix is defined by the change of elements of rows and columns.

B A −1 TA A B == B RRR . (2.7)

The program MathCAD Symbolics helps us to calculate and we can easily demonstrate that A −1 TA the inverse of the rotation matrix is equal to its transpose. B = B RR , because the nominator of elements in rotation matrix R−1 is equal to one.

⎛ cos()α −sin()α 0 ⎞ R := ⎜ ⎟ ⎜ sin()α cos()α 0 ⎟ ⎝ 0 0 1 ⎠ ⎛ cos()α sin()α 0 ⎞ T ⎜ ⎟ R → ⎜ −sin()α cos()α 0 ⎟ ⎜ ⎟ ⎝ 0 0 1 ⎠

⎡ cos()α sin()α ⎤ 0 ⎢ ()cos()α 2 + sin()α 2 ()cos()α 2 + sin()α 2 ⎥ ⎢ ⎥ − 1 R → ⎢ −sin()α cos()α ⎥ 0 ⎢ ()cos()α 2 + sin()α 2 ()cos()α 2 + sin()α 2 ⎥ ⎢ ⎥ ⎣ 0 0 1 ⎦

34 The matrix with orthogonal elements the norm of which is equal to 1 (orthogonal unit vectors) is called orthonormal. The transposed matrix is the matrix with transposed rows and columns. The inverse matrix is calculated by the formula

1 R−1 = R ),( (2.8) det R ji where Rji is an adjunct matrix. The inverse matrix of the orthonormal matrix is equal to the transposed matrix. Because the rotation matrix is orthonormal, its inverse matrix can be found as its transpose.

The product of the matrix and its inverse gives a unit matrix. The unit matrix has diagonal elements equal to 1, and all other elements equal to 0.

The scalar product of matrixes can be calculated by using the formula:

n cabik =⋅∑(ij ik ). (2.9) j=1

The formula can be used for the calculation of product 2.6. In this case the matrix aij is the B r A r rotation matrix and bjk is the position vector P . The result cik is the position vector P , where (i = 1...3; j = 1...3; k = 1).

r The general transform of the position vector, the vector B P given in translated and rotated coordinates {B} in the relation of base coordinates {A} can be described by the formula

A ABA rrr B +⋅= PPRP BO . (2.10)

r The vector AP can also be calculated by the transformation matrix

A r BA r B ⋅= PTP , (2.11)

A where BT is the transformation matrix to transform translated and rotated coordinates {B} to the base coordinates {A}. The procedure is called as the Homogeneous Transform.

The transformation matrix to transform coordinates {B} includes 3x3 rotation matrix and 3x1 position vector of origin coordinates {B} in the relation of coordinates {A}. The formula 2.11 can be shown as follows:

⎡ ⎤ ⎡ ⎤ ⎡ ⎤ ⎢ AP⎥ ⎢ A A ⎥ ⎢ B PPR ⎥ ⎢ ⎥ = ⎢ B BO ⎥ ⋅ ⎢ ⎥. (2.12) ⎢ _ ⎥ ⎢ ____ ⎥ ⎢ _ ⎥ ⎢ ⎥ ⎢ ⎥ ⎢ ⎥ ⎣ 1 ⎦ ⎣ 1000 ⎦ ⎣ 1 ⎦

Addition of the last row [0 0 0 1] is a mathematic manipulation to get 4x4 square matrix.

35 The use of transformation matrixes (transformation operators) helps us to describe different spatial vectors in different coordinates. For example, we can describe the motion of multi link manipulators and to solve the direct and inverse kinematics tasks of manipulators. The general transformation can be replaced by separate translation and rotation transforms and the corresponding transform operators.

⎡ 001 qX ⎤ ⎢ 010 q ⎥ QQTRANS ),( = ⎢ Y ⎥ (2.13) ⎢ 100 qZ ⎥ ⎢ ⎥ ⎣ 1000 ⎦ where Q is the vector and Q its module.

⎡ − αα 00sincos ⎤ ⎢ αα 00cossin ⎥ ZROT α),( = ⎢ ⎥, (2.14) ⎢ 0100 ⎥ ⎢ ⎥ ⎣ 1000 ⎦ where Z defines the rotation around z-axis and α the rotation angle.

The separate translation and rotation operators can be combined in one transformation operator (transformation matrix).

Several sequential transforms can be combined in one. The transform equations:

B CB rr A r BA r C ⋅= PTP and B ⋅= PTP can be combined in the following equation:

A r A CB r B C ⋅⋅= PTTP . (2.15)

Transformation matrix for the combined transform ⎡ ⎤ rr ⎢ A ⋅ B BA +⋅ APPRRR ⎥ AT = ⎢ B C B CO BO ⎥. (2.16) C ⎢ ____ ⎥ ⎢ ⎥ ⎣ 1000 ⎦

B Inverse transform matrix AT can be presented as follows:

⎡ ⎤ r ⎢ RTA ⋅− ATA PR ⎥ BT = ⎢ B B OB ⎥ (2.17) A ⎢ ____ ⎥ ⎢ ⎥ ⎣ 1000 ⎦

B A −1 or A = BTT .

36 B The transformation matrix AT is not orthonormal (consisting only of orthogonal unit vectors) and therefore its inverse matrix is not equal to the transposed matrix.

By solving transform equations it is possible to find solutions for any unknown transform if sufficient transform conditions exist. For example, if we know the conditions

E E A E E B C D A ⋅= DTTT and D B C ⋅⋅= DTTTT

E A E B C then A D B C ⋅⋅== DTTTTT .

Consequently,

B E −1 A C −1 C B D ⋅⋅= DTTTT . (2.18)

Euler angles. The rotation matrix is not the only way to define the orientation of a body. We can define the orientation of a body also by three independent angles. The nine elements of the rotation matrix are mutually dependent and there are six conditions, including three conditions for the longitude of the unit vector

Xˆ = ;1 Yˆ = ;1 Zˆ = ;1 (2.19) and three conditions for their orthogonal location exist.

YX ˆˆ =⋅ ;0 ZX ˆˆ =⋅ ;0 ZY ˆˆ =⋅ 0 (2.20)

The following calculation using the MathCAD program illustrates the issue of scalar or dot product and cross product of orthogonal vectors. The dot product of two orthogonal or parallel vectors with magnitude 5 gives

⎜⎛ 0 ⎞⎟ ⎜⎛ 5 ⎞⎟ ⎜⎛ 5 ⎟⎞ ⎜⎛ 5 ⎞⎟ ⎜ 5 ⎟⋅⎜ 0 ⎟ = 0 ⎜ 0 ⎟⋅⎜ 0 ⎟ = 25 ⎜ ⎟ ⎜ ⎟ ⎜ ⎟ ⎜ ⎟ ⎝ 0 ⎠ ⎝ 0 ⎠ ⎝ 0 ⎠ ⎝ 0 ⎠

r The cross product of the same vectors r r banba ⋅⋅⋅=× sinα gives

⎜⎛ 5 ⎟⎞ ⎜⎛ 0 ⎟⎞ ⎜⎛ 0 ⎞⎟ ⎜⎛ 5 ⎞⎟ ⎜⎛ 5 ⎟⎞ ⎜⎛ 0 ⎟⎞ ⎜ 0 ⎟ × ⎜ 5 ⎟ = ⎜ 0 ⎟ ⎜ 0 ⎟ × ⎜ 0 ⎟ = ⎜ 0 ⎟ ⎜ ⎟ ⎜ ⎟ ⎜ ⎟ ⎜ ⎟ ⎜ ⎟ ⎜ ⎟ ⎝ 0 ⎠ ⎝ 0 ⎠ ⎝ 25 ⎠ ⎝ 0 ⎠ ⎝ 0 ⎠ ⎝ 0 ⎠ ,

r where the resultant vector nr is orthogonal to the unit vector ar and b . Hence, the scalar or dot product of two orthogonal vectors is equal to zero, but their cross product is an orthogonal vector the magnitude of which equals the scalar product of two magnitudes.

To conclude we can declare that any rotation of the coordinate system can be described by three independent variables. Mostly three independent angles: roll, pitch and yaw angles are used in this case (Fig. 2.4). The rotation angle on yz-plane if rotation happens around x axis is defined by the roll angle α, the rotation angle on xz-plane if rotation happens around y axis is

37 defined by the pitch angle β and the rotation angle on xy-plane if rotation happens around z axis is defined by the yaw angle γ. Sometimes these angles are also called X, Y, Z angles.

ROLL PITCH YAW

zA zA zA α

zB zB yB zB yB yB γ yA β yA yA

xB xB xA xA xA xB

Figure 2.4 Roll, pitch and yaw angles of manipulator’s gripper or tool

Three possible rotation angles are needed for free orientation in space. These are essential for control of aircraft (Fig. 2.5, a) or human head (Fig. 2.5, b) motion.

a Yaw b Yaw Middle sags plane Middle frontal plane

y axis x axis

Pitch Roll Pitch Roll

z axis

Figure 2.5 Roll, pitch and yaw angles of aircraft a and human head b

General rotation matrix for three rotation angles can be found from separate rotation matrixes for angles α, β and γ.

AAA A BR(,,γ β α )= ROT ( ZB ,α )⋅ ROT ( YB ,)β ⋅ ROT ( XB ,),γ (2.21) where ⎡ − αα 0sc ⎤ AZROT α),( = ⎢ αα 0cs ⎥ B ⎢ ⎥ ⎣⎢ 100 ⎦⎥

38 ⎡ s0c ββ ⎤ AYROT β ),( = ⎢ 010 ⎥ B ⎢ ⎥ ⎣⎢− c0s ββ ⎦⎥ ⎡ 001 ⎤ AXROT ),( = ⎢ − sc0 γγγ ⎥ B ⎢ ⎥ ⎣⎢ cs0 γγ ⎦⎥

In this case and also in future examples the first letters s and c are used instead of functions sine and cosine to reduce the formula.

General rotation matrix for angles α, β and γ is

⎡ ⋅+⋅⋅⋅−⋅⋅⋅ sscsccsscccc γαγβαγαγβαβα ⎤ AR αβγ ),,( = ⎢ ⋅−⋅⋅⋅+⋅⋅⋅ sccssccssscs γαγβαγαγβαβα ⎥ (2.22) B ⎢ ⎥ ⎣⎢ − ⋅scs γββ ⋅cc γβ ⎦⎥ The MathCAD program is very convenient for the calculation of matrix products. For symbolic calculations the toolbox MathCAD Symbolic can be used. The following example shows the use of MathCAD Symbolic toolbox for the calculation of matrixes product using symbolic elements.

⎛ cos()α −sin()α 0 x ⎞ ⎜ ⎟ sin()α cos()α 0 y T1 := ⎜ ⎟ ⎜ 0 0 1 z ⎟ ⎜ ⎟ ⎝ 0 0 0 1 ⎠ ⎛ cos()β −sin()β 0 a ⎞ ⎜ ⎟ 0 0 1 0 T2 := ⎜ ⎟ ⎜ sin()β cos()β 0 h ⎟ ⎜ ⎟ ⎝ 0 0 0 1 ⎠

TT1:= ⋅T2

⎛ cos()α ⋅cos()β −cos()α ⋅sin()β −sin()α cos()α ⋅a + x ⎞ ⎜ ⎟ sin()α ⋅cos()β −sin()α ⋅sin()β cos()α sin()α ⋅a + y T → ⎜ ⎟ ⎜ sin()β cos()β 0 hz+ ⎟ ⎜ ⎟ ⎝ 0 0 0 1 ⎠

The transformation matrix written in the symbolic mode can be used for solving tasks of inverse kinematics. In this case the links of rotation angles α and β will be determined if the gripper positioning coordinates x, y and z are known.

39 2.2. Description of manipulator kinematics

Control procedure of a includes several sequential steps to realize the program instruction and reference motion between a given starting and a destination positioning point (x2, y2, z2) in a robot’s working envelope. Generally these steps are as follows:

1. Detection of signals from position sensors located on the drive motor shaft and determination of rotation angles (e.g. αa, βa, γa) of manipulator links in the joint coordinate system. 2. Calculation of the real location of the manipulator gripper or the tool in the base or world Cartesian coordinate system xa, ya, za, i.e. solving the direct kinematics task of the manipulator using angles (αa, βa, γa) in joint coordinates. 3. Comparison of the real position with the given motion destination point location in the base or world coordinates; planning of motion trajectory between the start and destination points in a robot’s working envelope space; determination of reference time diagrams for position, velocity, acceleration and jerk of manipulator gripper or tool, using linear or circular interpolation for trajectory generation. 4. Determination of motion time dependent reference coordinates in the Cartesian coordinate system (projections xr, yr, zr). 5. Determination of motion time dependent joint reference coordinates (αr, βr, γr), i.e. solving the inverse kinematics tasks of the manipulator and transfer of the reference signals to manipulator joint drives. 6. Cyclic repeating of steps 1…5 and stopping the motion in the destination positioning point.

The flow diagram for the trajectory and motion control of manipulator is shown in Fig. 2.6.

Direct kinematics of a manipulator To solve a direct kinematics task of a manipulator, the position of the gripper or the tool centre point and gripper or tool orientation coordinates in the base or world coordinates are calculated if the joint angles measured by drive sensors are known in joint coordinates. In other words, the gripper or tool location is calculated according to the measured angles of manipulator joints (links).

Inverse kinematics of a manipulator To solve an inverse kinematics task of a manipulator, the location of all manipulator joints (links) in joint coordinates is calculated if the gripper or tool reference position and orientation angles are calculated by the trajectory planner in the base or world Cartesian coordinates.

Methods for solving direct kinematics tasks ƒ Geometric method (using basic formulas of geometry and trigonometry) ƒ Matrix method (using transformation matrixes of coordinate systems)

Methods for solving of inverse kinematics tasks ƒ Definition of manipulator joints relative locations (pose) if multiple solutions exist.

40 ƒ Closed form solutions and iterative numerical solutions. Generally all systems with revolute and prismatic joints having a total of six degrees of freedom (DOF) as a single series chain are solvable.

START

Motion instruction and x2, y2, z2 destination point coordinates

Determination of real position in αa, βa, γa joint coordinates

Solving of direct kinematics tasks xa, ya, za of the manipulator and determination of the position in base coordinates

xs, ys, zs Trajectory planning and generation of reference motion in base coordinates

αs, βs, γs Solving of inverse kinematics task of manipulator and determination of reference signals for drives α , β , γ s s s Transfer of reference signals to drives

As = Aa? Control of positioning in destination point

END

Figure 2.6 The flow diagram for the trajectory and motion control of the manipulator

The direct kinematics task of a manipulator is solved using transformation matrixes of coordinate systems. The inverse kinematics task of a manipulator can be solved by the use inverse transform matrixes. In some cases the inverse kinematics task has multiple solutions and to select one of them is an additional problem. For example articulated hand with two links of a manipulator has two possible poses to reach the reference end point (Fig. 2.7 a). The number of possible poses depends on the construction of the manipulator kinematics chain. The manipulator of a PUMA robot has four poses to reach the defined space coordinates of end effectors, i.e. the gripper or tool (Fig. 2.7 b). If the pose of the manipulator is defined, in the case of a single series chain and six links, only one solution exists. The pose must be defined during programming or before the motion start of the robot because in the case of continuous motion the change of pose is not possible (Fig. 2.8).

41

Figure 2.7 Different poses of an hand a, and manipulator of PUMA robot b if end effector coordinates are referred to

y

L12 o A2 y

o A2

A1 o

A1 o

-x 0 x -x 0 x

Figure 2.8 Example of linear motion using articulated robot hand and impossible change of pose during this motion

To solve the inverse kinematics task of a manipulator, the roll, pitch and jaw angles of robot hand must be calculated using numerical values of given rotation matrix elements. If the rotation matrix has numerical elements rij

⎡ rrr 131211 ⎤ AR = ⎢ rrr ⎥ (2.23) B ⎢ 232221 ⎥ ⎣⎢ rrr 333231 ⎦⎥ and if we compare matrixes 2.22 and 2.23 and their elements, the angles of the orientation of the coordinate system can be calculated as follows:

42 γ = 32 β rrA 33 β )cos/,cos/(2tan 2 2 β = (2tanarc 11,31 +− rrr 21 ) (2.24)

α = 21 rr 11 ββ )cos/,cos/(2tanarc where arctan2(rij) is the function of two arguments (y, x). For example, arctan2(2, 2) = 45°.

Inverse kinematics equations can be solved using the MathCAD program and its operators Given and Find

α :=0 β := 0 r1 := 6 r2 := 4

Given ()cos()α ⋅cos()β sin()α ⋅− sin()β ⋅r2 ()cos()α ⋅+ r1 6

()sin()α ⋅cos()β cos()α ⋅+ sin()β ⋅r2 ()sin()α ⋅+ r1 4

⎛ α ⎞ ⎜ ⎟ := Find()αβ, ⎝ β ⎠

α → 0 1 β π⋅→ 2

The inverse kinematics equations are often transcendental equations, i.e. these equations have a solution that can not be described analytically with the help of known mathematical expressions. The transcendental equations can be solved numerically. The other way to solve the transcendental equations is using supplementary auxiliary functions and substitute variables.

The trigonometric functions can be replaced with new algebraic functions and a new variable u. u = ()α 2/tan 1− u2 cosα = (2.25) 1+ u2 2u sinα = 1+ u2

After that substitution, the transcendental equations are transformed to polynomials that have an analytical solution.

43 2.3. Transform of velocity and torque vectors

The transform of velocity, force and torque vectors is different from the transform of position vectors, because in this case the point of vector application is not always essential, i.e. the vector can be translated if its magnitude and direction stay unchanged. These vectors are named free vectors and their magnitude and direction do not depend on the point of vector application.

The transform of vectors belongs to the field of linear algebra and the mathematical methods and formulas for the vector transform are described in textbooks of the same course. The formulas given in this chapter help us to solve the kinematics tasks of robots and to analyze the matematical problems of robot control.

The transform of free vectors. The torque vectors can be transformed by using the rotation matrix, because the position vector of the origin point of the coordinate system is not essential for free vector transformation

A BA Torque B ⋅= NRN Torque (2.26)

The transform of the velocity vector

A r BA r Velocity B ⋅= VRV Velocity (2.27)

The conclusion is that the rotation of the coordinate system does not influence the magnitude and direction of the vector, but changes the description of the vector.

Transformation of velocity vectors on translation. If a coordinate system {B} moves in A r relation to a rotated coordinate system {A} with a velocity of VB0 , the velocity of the linearly moving point in the coordinates {B} can be transformed to coordinate system {A} using the following equation:

A r A r BA r P 0 BB ⋅+= VRVV P (2.28)

A r If the coordinate system {B} rotating with an angular, velocity of ΩB in relation to the r coordinate system {A}, the linear velocity of vector B P point given by position in the coordinate system {B} can be calculated in the coordinate system {A} by the equations:

r r A ⋅= BA PRP B (2.29) A r A r A r VP B ×Ω= P

For vector variables the last equation has the same meaning as the equation: v ω ⋅= r used for scalar variables, where r is the radius and v the linear velocity.

Generally, if a point moves in relation to the rotating coordinate system {B} with a linear B r velocity: VP , this motion can be transformed to the coordinate system {A} using the following equation:

44 A r A B r A r A r P ()VV P B ×Ω+= P or (2.30)

A BA A BA rrrr BP VRV P BB ⋅×Ω+⋅= PR (2.31)

If the coordinate system {B} rotates and translates simultaneously the transformation of the velocity vector can be done by equation (2.32) similar to (2.31), but in this case the velocity vector of the origin point of coordinates {B} must be added.

A A BA rrr A r BA r P 0 BB VRVV P BB ⋅×Ω+⋅+= PR (2.32)

Velocities of manipulator links The planar manipulator on the xy-plane is shown in Fig. 2.9. The stationary base coordinates of the manipulator are x0y0. Around the origin of coordinates (point O) rotates link 1 having longitude L1. The second link has longitude L2 and is connected with the revolute joint to link 1. The relative rotation angles of links are α1 and α2. The angular velocity is the derivative of angular position. Consequently

dα1 & == ωα 11 dt (2.33) dα2 & == ωα 22 dt

The angular velocities of links in the stationary base coordinates if rotating around z-axis are

⎡ 0 ⎤ ⎡ 0 ⎤ r r r r 0 =Ω ⎢ 0 ⎥ 0 =Ω ⎢ 0 ⎥ 0 0Ω=Ω (2.34) 1 ⎢ ⎥ 2 ⎢ ⎥ 3 2 ⎣⎢ω1 ⎦⎥ ⎣⎢ + ωω 21 ⎦⎥

V3 x3

y3

L2

V2 x2 α2

y2

y0 y1 x1 L1 α1 V1 = 0 O x0

Figure 2.9 Planar articulated hand of the manipulator

The linear velocity vector of the origin point of the coordinate system is defined by projections of the velocity vector to the corresponding axes of the coordinate system.

45

⎡0⎤ ⎡L sinαω 211 ⎤ ⎡ L sinαω 211 ⎤ r r r 1V = ⎢0⎥ 2V = ⎢L cosαω ⎥ 3V = ⎢L cos L ++ ωωαω ⎥ (2.35) 1 ⎢ ⎥ 2 ⎢ 211 ⎥ 3 ⎢ (212211 )⎥ ⎣⎢0⎦⎥ ⎣⎢ 0 ⎦⎥ ⎣⎢ 0 ⎦⎥

The manipulator has the following rotation and translation matrixes:

⎡ − sc 11 0⎤ ⎡ − sc 22 0⎤ ⎡ 001 ⎤ 0R = ⎢ cs 0⎥ 1R = ⎢ cs 0⎥ 2R = ⎢ 010 ⎥ (2.36) 1 ⎢ 11 ⎥ 2 ⎢ 22 ⎥ 3 ⎢ ⎥ ⎣⎢ 100 ⎦⎥ ⎣⎢ 100 ⎦⎥ ⎣⎢ 100 ⎦⎥ and

⎡ − sc 11 00 ⎤ ⎡ − 22 0 Lsc 1 ⎤ ⎡ 001 L2 ⎤ ⎢ cs 00 ⎥ ⎢ cs 00 ⎥ ⎢ 0010 ⎥ 0T = ⎢ 11 ⎥ 1T = ⎢ 22 ⎥ 2T = ⎢ ⎥ (2.37) 1 ⎢ 0100 ⎥ 2 ⎢ 0100 ⎥ 3 ⎢ 0100 ⎥ ⎢ ⎥ ⎢ ⎥ ⎢ ⎥ ⎣ 1000 ⎦ ⎣ 1000 ⎦ ⎣ 1000 ⎦

The summary rotation matrix is

⎡ 12 − sc 12 0⎤ 0 0 1 2RRRR =⋅⋅= ⎢ cs 0⎥ (2.38) 3 1 2 3 ⎢ 12 12 ⎥ ⎣⎢ 100 ⎦⎥ where

−= ssccc 212112 = cos(α +α21 )

+= sccss 212112 . = sin(α +α21 )

The velocity vector in stationary base coordinates will be calculated as the product of the A r BA r rotation matrix with the eienvalue of velocity ( Velocity B ⋅= VRV Velocity ). Because the first coordinates are stationary in relation to base coordinates, then

⎡0⎤ r 0V = ⎢0⎥ 1 ⎢ ⎥ ⎣⎢0⎦⎥

The velocity of an object moving in the second coordinate system can be transformed to the base coordinate system as follows:

0 r 20 r 22 ⋅= VRV 2

⎡ L sinαω 211 ⎤ r where 2V = ⎢L cosαω ⎥ 2 ⎢ 211 ⎥ ⎣⎢ 0 ⎦⎥

46 ⎡− L sin()αω 111 ⎤ r and 0V = ⎢ L cos αω ⎥ (2.39) 2 ⎢ 11 ()1 ⎥ ⎣⎢ 0 ⎦⎥

⎡ L sinαω 211 ⎤ r 3V = ⎢L cos L ++ ωωαω ⎥ (2.40) 3 ⎢ (212211 )⎥ ⎣⎢ 0 ⎦⎥

⎡− L sin L ( +− 212111 ) [sin( +ααωωαω 21 )]⎤ rr r 0 ⋅= 30 VRV 0V = ⎢ L cos L ++ cos +ααωωαω ⎥ (2.41) 33 3 3 ⎢ ()(212111 [21 )]⎥ ⎣⎢ 0 ⎦⎥

The solution can be easily found with the help of theMathCAD Symbolic program.

MathCAD calculates

Using the operator Simplify we get the following matrix expression:

Jacobian matrixes or Jacobians are used to describe of multidimensional derivatives of vectors. Because the velocity vector is the time related derivative of the position vector, the velocity vectors can be found using Jacobians. In the case of the six coordinate (six links) manipulator the Jacobian is a matrix with dimensions 6 x 6. The Jacobian of the manipulator with two coordinates (see Fig. 2.11) has dimensions 2 x 2.

r r 00 JV Ω⋅=

Jacobian matrix consists of components of linear velocity vectors ω1 and ω2. For previously 3 r 0 r described vectors V3 ja V3

⎡ L sinαω 211 ⎤ ⎡− L sin L ( +− 212111 )([]sin +ααωωαω 21 )⎤ r r 3V = ⎢L cos L ++ ωωαω ⎥ and 0V = ⎢ L cos L ++ cos +ααωωαω ⎥ 3 ⎢ (212211 )⎥ 3 ⎢ ()(212111 []21 )⎥ ⎣⎢ 0 ⎦⎥ ⎣⎢ 0 ⎦⎥ the following Jacobians or Jacobian matrixes can be found:

47 3 ⎡ sL 21 0 ⎤ 0 ⎡ 12211 −−− sLsLsL 122 ⎤ J ()α = ⎢ ⎥ J ()α = ⎢ ⎥ (2.42) ⎣ + LLcL 2221 ⎦ ⎣ + 12211 cLcLcL 122 ⎦

In the base coordinates the velocity vector can be found as the product of Jacobian and angular velocities. The example of this product is calculated with the help of the MathCAD Symbolic program.

⎛ L1⋅ sin(α2) 0 ⎞ ⎛ ω1 ⎞ ⎡ L1⋅ω sin(α2) ⋅ 1 ⎤ ⎜ ⎟ ⋅⎜ ⎟ → ⎢ ⎥ ⎝ L1⋅ cos()α2 + L2 L2 ⎠ ⎝ ω2 ⎠ ⎣()L1⋅ cos()α2 + L2 ⋅ω1 L2⋅+ ω2⎦

⎛ −L1⋅sin(α1) L2⋅− sin(α1 + α2) −L2⋅sin(α1 + α2) ⎞ ⎛ ω1 ⎞ ⎡ (−L1⋅sin(α1) L2⋅− sin(α1 + α2)) ⋅ω1 − L2⋅ω sin(α1 + α2) ⋅ 2 ⎤ ⎜ ⎟ ⋅⎜ ⎟ → ⎢ ⎥ ⎝ L1 cos()α1 L2⋅+ cos()α1 + α2 L2⋅ cos()α1 + α2 ⎠ ⎝ ω2 ⎠ ⎣ ()L1⋅ cos()α1 L2⋅+ cos()α1 + α2 ⋅ω1 + L2⋅ω cos()α1 + α2 ⋅ 2 ⎦

2.4. Kinematics chains of manipulators

The kinematics chains of manipulators are composed from spatially coupled joints. The number of joints and types of kinematics pairs determines the manipulator’s degree of freedom (DOF). For spatial transfer and orientation of objects the manipulator must have minimally six degrees of freedom (three of them for object translation and other three for object orientation). To use all six degrees of freedom, a robot must have six drives, each of which realizes one motion in one coordinate. Possible spatial motions and kinematics pairs used in robots are shown in Fig. 2.10.

All mechanisms can be divided into planar and spatial mechanisms. Description of these mechanisms is on website http://www.cs.cmu.edu/People/rapidproto/mechanisms/chpt4.html

Joints of kinematics chains are coupled with the help of kinematics couplings. In the case of planar mechanisms, the kinematics pairs of the fifth order are used. The kinematics pairs of the fifth order are revolute pairs and prismatic pairs.

The kinematics behaviours of kinematics couplings are defined by degrees of freedom, DOF and constraints:

0 degrees of freedom - 6 constraints 1 degree of freedom – 5 constraints – the kinematics pair of the fifth order 2 degrees of freedom – 4 constraints – the kinematics pair of the fourth order etc.

Most of manipulators have kinematics joints with revolute and prismatic pairs (Fig. 2.10). The revolute pair R allows rotational and prismatic pair T translational motion in one coordinate of polar, angular or Cartesian coordinate system.

Each revolute or prismatic kinematics pair gives one degree of freedom to a manipulator. Consequently, for full spatial motion and orientation of objects a six link manipulator with revolute or prismatic pairs is needed.

48 Some manipulators have links joined with kinematics pairs having more than one degree of freedom. For example, spherical joint has three degrees of freedom (three constrains) and is considered as the joint of the third degree. In the case of the fourth or third degree joints in the manipulator chain, the number of manipulator links needed for full spatial motion is less than six.

Generally the number L of the degrees of freedom can be calculated from the structural equation of kinematics chain.

23456 −−−−−= pppppnL 12345 , (2.43) where n is the number of moving links in the chain and p1…p5 is the number of kinematics pairs of different order.

a b z

y

x

Figure 2.10. Possible motions of an object in space a and kinematics pairs of yhe fifth order b

The formula (2.43) can be used to calculate the number of degrees of freedom of different manipulation mechanisms. It can also be used to calculate the number degrees of freedom of a human hand. Regarding, that a human hand has three links: upper arm, forearm and flat of the hand and each link has spherical joints, the number of degrees of freedom of human hand is

pnL 3 −⋅=−= ⋅ = 9333636 (2.44)

If the kinematics chain of the manipulator contains only kinematics pairs of the fifth order, then

−= 56 pnL 5 (2.45)

In some cases the total number degrees of freedom of the manipulator is less than six and the robot cannot be used for universal orientation of objects in space. To use a manipulator having less than 6 degrees of freedom, in industry the additional mechanism of orientation must be added to the robot system. Objects can be put in order, e.g. on the feeding conveyor.

In the case of the manipulator with planar mechanism the lower kinematics pairs (revolute and prismatic pairs) can form 2n different structures of kinematical chains (where n is the number of series links in the chain).

49

In the case of manipulator with spatial mechanism each kinematics pair has its own axis that can be oriented in different ways in relation to the base coordinate system. In addition, the centre of revolute or prismatic kinematics pair may not lie on the axis of the former link. Consequently, the number of potential kinematics structures of manipulators is much higher. If kinematics pairs are freely oriented in space, the number of possible structures is infinite. Normally, most of the manipulators have kinematics pairs with parallel or orthogonal orientation.

All manipulators have a stationary fixed link, as a base link in the kinematical chain that is not considered if different kinematics chains are compared. So the manipulator consisting of a stationary link and three other links are considered a three link manipulator. The first kinematics pair couples the stationary link with the first moving link in the chain.

The motion of multi-link manipulation mechanism and its possibility to manipulate objects in space depends on the types of kinematics pairs and their degrees of freedom (Fig. 2.11).

Type of pair o coupl DOF DOF o coupl Order Order Order Order Type 1 Type 2 Type 3 N N

Figure 2.11 Order of kinematics pairs and their degrees of freedom

50 The transport mechanism of manipulator (arm of the manipulator) has normally three links the construction and kinematics pairs for their coupling are essential for the external image of the manipulator as well as for motion extension and handling capacity. More than three links in the kinematics chain of the transport mechanism gives higher maneuverability of manipulator and higher flexibility of robot that helps to work in complex work spaces, including obstacles in the working envelope. Its weakness is the higher complexity of construction. Therefore, normal industrial robots have a minimal number of links: three for transportation and three for orientation.

The orientation mechanism of the manipulator (wrist of the manipulator) is very compact, its motion extension is small and its effect on the external image of the robot is also small. Normally three links with revolute kinematics pairs are used in the wrist mechanism.

Kinematics pairs, coupling transport links of the manipulator mechanism define also the coordinate system of the manipulator used to describe of motion. If three translational linearly moving links are used, the manipulator is working in Cartesian coordinates with three orthogonal axes. If two linear translational motions and one rotational motion are used, the manipulator is working in the cylindrical coordinate system. If two rotational motions and one linear translational motion are used, the manipulator is working in the spherical coordinate system. And finally, if the manipulator has an articulated arm, its motion can be described in cylindrical or spherical angular coordinate systems.

2.5. Manipulator in Cartesian coordinate system

A manipulator working in the Cartesian coordinate system shown in Fig. 2.12 uses three links with linear translational motion and is known as a gantry robot. The working envelope of a gantry robot has the form of right parallelepiped with dimensions a, b, h that determines the extension of motion. Dimensions L, M and H determine the location of the working envelope in Cartesian coordinates 0xyz.

x

y

z

Figure 2.12 Manipulator in the Cartesian coordinate system

Kinematics tasks in Cartesian coordinates can be easily solved because the direction of each link motion can be selected in the direction of orthogonal axes.

51 2.6. Manipulator in cilindrical coordinate system

The working envelope of a manipulator in the cylindrical coordinate system is the part of a hollow cylinder. Examples of manipulators in the cylindrical coordinate system are shown in Figs. 2.13 and 2.14. The base or the world coordinate system is bound to the manipulator stationary base. More information about manipulator coordinate systems can be found from website http://prime.jsc.nasa.gov/ROV/types.html

Figure 2.13. Manipulator in the cylindrical coordinate system: a working envelope for vertical axis robot, b working envelope for horizontal axis robot, examples of Versatran, Seiko RT3300 and Fanuc M300 robots

The following is the mathematical description of the manipulator shown in Fig 2.14.

Position vector

px r PA = p y , (2.46)

pz where

52 x cosα += Rbp cos()α + αc

y Rbp sinsin (++= ααα c ) (2.47)

z += hZp

z0

y3 z2 R z1 y2 x3

y1 z3 x2 h PA A x1

α b αc

Z

y0

α x0

Figure 2.14 Calculation scheme for the manipulator working in the cylindrical coordinate system

Equations describing geometrical components of the position vector can be used to solve manipulator kinematics tasks. This method is named the geometrical method of solution of manipulator kinematics tasks. Complexity of the equations and their solving procedure depends on the configuration of the manipulator and used coordinate system. Principally, these equations can be used for direct as well as for indirect kinematics tasks. Difficulties can exist if the equations are transcendental. In this case there are no general solutions but only numerical values for solution exist.

Rotation matrixes

− αα 0sincos cos c − αα c 0sin 0 1 1 R = αα 0cossin 2 R = c αα c 0cossin (2.48) 100 100

Transformation matrixes

00sincos − 001 R − αα cos c − αα c 0sin b αα 00cossin αα 00cossin 0100 0T = 1T = c c 2T = (2.49) 1 100 Z 2 100 h 3 0010 1000 1000 1000

Articulated arm manipulator working in cylindrical coordinates (i.e. SCARA-type manipulator) has also a hollow cylinder form working envelope. It must be added that the cylinder axis may be vertical or horizontal. That kind of robots are shown in Fig. 2.15. The kinematics of the SCARA-type robot is shown in Fig. 2.16.

53 The motion of the horizontal articulated arm robot is described by simple equations and a simple solution exists for direct as well as for indirect kinematics tasks. The position of manipulator’s tool or gripper is defined by point A, location of which may be determined in the Cartesian coordinates 0xyz or in cylindrical coordinates 0α1α2z.

Figure 2.15 Articulated arm robots working in the cylindrical coordinate system: with the horizontal axis and vertical axis

z0 z2

y2 y3 yA y z1 y1 x3 z L1 x1 x2 3

PA A α1 b α2 α1 L2 Z

xA A x α2 y 0

x0

Figure 2.16 Calculation scheme for the articulated arm robot working in the cylindrical coordinate system

The manipulator direct kinematics task can be solved using the following system of equations:

a cosα += LLx 211 cos(α +α21 )

a sin LLy sin(++= ααα 21211 ) (2.50)

= zz aa

Using equations (2.50) it is possible also to solve the inverse kinematics task of the manipulator, but it must be considered that the calculation of angles α1, and α2 may be complicated. Because of this the other solution based on the geometrical construction in Fig. 2.17 can be used to solve the inverse kinematics task of the manipulator.

54

y y c e φ2

L1 φ1 h d α1e L2 φ3

xe A x α2e

Figure 2.17 Geometrical solving of the inverse kinematics task of the planar articulated arm and determination of

angles α1e and α2e if the position reference point Ae (xe, ye) is given

If the manipulator inverse kinematics task is solved using the geometrical method, the triangles in Fig. 2.17 can be formed and used to find the following equations:

r += dc

22 += yxr ee (2.51) 2 2 1 −= cLh

2 2 2 −= dLh

The variable c can be found from the two last equations of (2.51).

2 2 −+ LLr 2 c = 1 2 (2.52) 2r

The following angles can be found from Fig. 2.17:

ϕ1 = arctan()ee xxy e > 0kui,

1 = πϕ xe = 0kui,2 (2.53)

1 πϕ += arctan()ee xxy e < 0kui,

ϕ2 = arctan()ch

ϕ3 = arctan()dh

The angles 2.53 can be used to find rotation angles of manipulator links α1e and α2e:

α e ϕ −= ϕ211

α e ϕ += ϕ322 (2.54)

The other way to solve the kinematics tasks of the manipulator is the algebraic method based on the transformation matrixes of the coordinate systems. The rotation and transformation matrixes are used.

55 In the case of the manipulator (Fig. 2.16), coordinate system 3 is rotated by 90º around z-axis of coordinate system 2 and then once 90º around x-axis.

Rotation matrixes

cos 1 − αα 1 0sin cos 2 − αα 2 0sin 0 1 (2.55) 1 R = 1 αα 1 0cossin 2 R = 2 αα 2 0cossin 100 100

Transformation matrixes

cos 1 − αα 1 00sin cos 2 − αα 2 0sin r1 100 r2 αα 00cossin sin αα 00cos 0001 0T = 1 1 1T = 2 2 2T = (2.56) 1 100 h 2 100 b 3 0010 1000 1000 1000

2.7. Manipulator in the spherical coordinate system

A manipulator in the spherical coordinate system is shown in Fig. 2.18. An articulated arm manipulator in spherical coordinates is shown in Fig. 2.19. The working envelopes of both manipulators have a hollow sphere form.

z

y x

x

Figure 2.18 Working envelope of the manipulator in the case of the spherical coordinate system

56 Wrist Upper arm

Elbow J5 axis Shoulder J4 axis

J6 axis J3 axis Mechanical interface for Õlavars Trunk connection of gripper

Shoulder J2 axis

Forearm J1 axis Base

Wrist

Figure 2.19 Articulated arm robots working in the spherical coordinates: a 6 DOF manipulator of Mitsubishi Co and b PUMA 560 manipulator of Unimation Co

z0 y3 b α3 z3 x3 α1

y4 y2 r1 r2 x2 x4 z2 PA z a A 4 α2 z1 h

y0 x1 y1

x0

Figure 2.20 Calculation scheme for the articulated arm manipulator working in the spherical angular coordinates

Coordinates of the manipulator second link (Fig. 2.20) are rotated 90º around z coordinate of the first link, rotated 90º around the x coordinate and then rotated by α2 around z-axis.

Transformation matrixes of coordinate systems:

cos 1 − αα 1 00sin 000 a αα 00cossin cos − αα 00sin 0 1 1 1 2 2 1T = 2T = 0100 2 αα 2 1cossin h 1000 1000

57 cos 1 − αα 1 0sin r1 100 r2 αα 00cossin 0010 2T = 1 1 3T = (2.57) 3 100 − b 4 − 0001 1000 1000

1 Rotation matrix of the component of the transformation matrix 2T can be found as the product of two rotation matrixes. The first describes the right angle rotation around z and x axis and the second describes the rotation by α2 around z axis.

100 cos 2 − αα 2 0sin 000 1 (2.58) 2 R = 001 × 2 αα 2 0cossin cos 2 −= αα 2 0sin

010 100 2 αα 2 1cossin

0 r 0 Position vector P in coordinates 0 can be found as the product of transformation matrix 4T r and vector 4P

0 r 40 r 4 ⋅= PTP

2.8. Multi-links and flexible links manipulators

An example of a multi-link manipulator is shown in Fig. 2.21. Manipulator’s tool or gripper position is controlled by changing the relative positions of links. The manipulator has very high maneuverability. The same properties may be achieved by using manipulators with flexible links. The control of the position of flexible links can be achieved, e.g. by using the magnetic field or electric current. That type of manipulators are not covered in this book.

Figure 2.21 Construction of a multi-link manipulator

58 2.9. Parallel kinematics of manipulators

Traditionally manipulators have a series configuration of links. In this case the drives of moving links are also located on the link chain and normally they are placed on previous links in relation to the moved link. It means that weight of each drive is a payload for the previous drive. In the case of wrist it is very difficult to locate massive drives near the gripper or tool. The solution is the location of all wrist drives on the last transportation link of the manipulator and use of complex multi-coordinate manipulator transmission gears (manipulator transmission mechanisms). With the help of these transmission mechanisms drives can be removed farther from the gripper or tool, but the weight of drives is still a problem in terms of better dynamical properties of a robot.

A new direction in the development of industrial is to use manipulators with parallel kinematics. Because these robots have totally different external image of the body of a traditional robot on several columns (legs), they are named as Trepod or (Fig. 2.22) or (Figs. 2.23 and 2.24). The same type of a robot is also the ABB robot FlexPicker. Additional information about manipulators with parallel kinematics is available on websites: http://www.parallemic.org/Terminology/General.html http://www.parallemic.org/SiteMap.html

Advantages of manipulators having parallel kinematics structure: ƒ 3-6 motors driving small weight links and one gripper or tool of a manipulator. Due to small weight and mass and little moment of inertia the robot has very high dynamic properties. ƒ positioning errors of links cannot be summed ƒ higher rigidity (mechanical accuracy) ƒ no moving connection cables ƒ higher accuracy and repeatability ƒ higher reliability

Robot image from website: http://www.parallemic.org/Reviews/Review002.html

Figure 2.22 Three-leg manipulator with parallel kinematics in the suspended pose

59

Moving platform Spherical joint S

Translational- pair P

Spherical joint S Fixed base

Figure 2.23 Six-leg moving platform (octahedral hexapod) or Stewarti platform

Image from website: http://www.parallemic.org/Reviews/Review012.html

Figure 2.24 Six-leg hexapod manipulator and its constructional components

M. Stewart widely known paper of about new type mechanism with 6 DOF was published in 1965. This mechanism was used in flying simulators for pilot training. Initial Stewart’s construction flying simulator was completely different from today’s construction, known as a octahedral hexapod, later named as Stewart’s platform. Another inventor of that kind of mechanism was engineer Klaus Cappel from the USA who has constructed a 6 DOF vibrating machine, very similar to a octahedral hexapod.

60 2.10. Kinematics of

The mobile robot can be automatically ground moving, flying, in water swimming or an automated submarine. The moving mechanism of a ground moving robot is a wheeled or crawled vehicle or different ledged mechanism.

If we consider the number of wheels and the type of the turning mechanism, the mobile robots based on wheeled vehicles can be divided into different groups:

• Three-wheel vehicle with one turning wheel and with one or two driving wheels; • The vehicle that can be turned by paired wheels; • Two- or four-wheel vehicle driving and with differential turning mechanism; • Vehicle with multi-wheel turning mechanism that allows turning if the center of the vehicle does not move; • Four-wheel vehicle with Ackermann’s turning mechanism (Ackermann’s turning mechanism is widely used in cars). In this case the inner wheel turns more than the outer wheel.

Turning of a wheeled vehicle is shown in Fig. 2.29. During turning on a curved way, the inner wheel goes a shorter way as compared with the outer wheel. Because of this wheels must have different angular speeds or one of the wheels must slip with curved motion. The different speeds for turning wheels can be achieved by using differential mechanisms.

R θ S1 = R θ Turning axis and turning radius

b

S = (R+b)θ 2

Figure 2.29 Turning pairs of wheels of a carriage

61 Turning of a wheel pair on the head of a carriage Turning of a wheel pair is the oldest method of turning a four-wheels carriages. Due to simplicity this method is also used today. This method gives geometrically the best turning, because both wheels have the same centre of turning. A weakness of this method is that the mechanism is clumsy and needs too much space for turning. It is very difficult to integrate the turning axis with carriage, because the wheels must be turned under the carriage (for smaller turning radius). This means that turning wheels must have a smaller diameter and the smaller stability of carriage during turning. Principally back wheels can be used for turning, but in this case the control of carriage turning on the forward motion is more complicated.

Examples of turning mechanisms are shown in Fig. 2.30. Similar to the wheel pair turning is the turning by using the revolute body joint of a vehicle. The vehicle with a central body joint is shown in Fig. 2.30 a. This type of a turning mechanism is very simple, but using the vehicle is complicated because of moving body parts. All vehicles having the rotating axis of two wheels are not stabile when turning in curve.

a b c

Turning centers

Turning centers

Turning by using a pair Turning of forward wheels by Controlled turning of of wheels and body joint Ackermann’s mechanism all wheels

Figure 2.30 Different constructions of the turning mechanism of a carriage

In 1816 Rudolf Ackermann found the main principle of the operation of an ideal turning mechanism - vertical surfaces of wheels must be orthogonal to the turning radius vector – and invented the turning mechanism that is wellknown today in all four-wheeled cars. Figure 2.31 a shows the four-link closed kinematics chain (car’s steering mechanism) that guarantees coinciding of the turning centers of wheels. In contrast, in the case of parallel wheels, turning centers of wheels do not coincide (Fig. 2.31 b) a lateral slip of wheels exists and consequently, the result is higher wearing and weaker stability.

62 a Ackermann’s turning mechanism b

R1

R2

Centre of turning

Figure 2.31 Ackermann’s mechanism (a) and unsuitable turning if turning wheels are parallel (b)

Control of turning of four-wheel vehicles Turning of all four wheels gives the best maneuverability. That kind of very flexible turning mechanism can be used to turn a vehicle if the center of turning is fixed. Control of the turning of all four wheels is useful and widely used in the case of robot vehicles. The following versions of turning control can be used:

• Proportional control by using the double Ackermann’s mechanism. Fore and back wheels of a vehicle will be turned proportionally by the turning radius. • Delayed non-proportional control when back wheels will be turned after the fore wheels have been turned by a certain angle. • Control by differential mechanism if inner and outer wheels during turning in curve have different angular speeds and turns of the vehicle. • Control by the turning of all wheels when the fore and back wheels will be turned in the opposite directions and the vehicle turns if its body centre does not move. • Control by using the reversible differential mechanism when a vehicle’s inner and outer wheels in curve are rotating in opposite directions and the vehicle turns if its body centre does not move. • Dog walk steering when the fore and back wheel will be turned in the same direction and the vehicle moves laterally.

Locomotion of mobile robots was studied in the USA in the University of Carnegie Mellon. In 2001 a PhD thesis Analytical Configuration of Wheeled Robotic Locomotion was published. Different methods to turn vehicle are shown in Fig. 2.32. If in the robot drive the differential mechanism is used and wheels are not turned in the curve, the lateral slip of wheels exist.

Control of four-wheel turning is used in the case of agricultural machines, construction machines, special vehicles and mobile robots.

63

Turning by Ackermann’s Turning by differential Turning by control of Turning by reversible double mechanism mechanism all wheels differential mechanism

Figure 2.32 Turning of a vehicle using different turning mechanisms

Problems of dynamical control of turning If a vehicle turns in curve, the effect of inertial forces on the vehicle and the lateral slip of wheels can happen. Turning the wheel more means that a higher slip has happened. A higher slip means that higher counterforce appears on the wheels, that compensates the centrifugal force generated by turning. It must be added that in curve the turning angle of the inner wheel and its slip are higher than the turning angle and the slip of the outer wheel. At the same time, the load (force) of the outer wheel is higher than the load of the inner wheel.

Figure 2.33 shows the problems of the dynamical effect of forces if turned in curve. The driving force, inertial force of a vehicle and the friction force on the rolling surface will have the sum effect on the wheel. If a vehicle moves at a uniform constant speed, the driving force Fv and friction force Fv are in same direction. In a curve the additional centrifugal force Fts that pushes the vehicle in the lateral direction to the wheel appears. If a wheel is in the direction of motion (Fig. 2.27, a), then the summary force pushes the vehicle out of curve. If the turning angle of the wheel is higher (Figs. b and c), it can be achieved that the direction of the summary force coincides with direction of motion. The wheel rolling and slipping conditions on the surface depend on the friction and profile of surface that is very uncertain and occasional. Therefore, the control of a vehicle in curve if riding conditions can change is very complicated and a danger exists that vehicle can lose its controllability.

a b c

α α

Fv Fv Fv

Fts Fts Fts

Fh Fh Fh

Figure 2.33 Turning of a wheel in curve: the wheel is in the direction of motion a, the wheel is turned to compensate centrifugal forces b, c

64 For small, simple and cheap robots to help turning in small places and to get higher maneuverability, the multi-directional wheels can be used (Fig. 2.34).

Figure 2.34 Examples of wheels rolling in two different directions

In the case of robots with wheeled vehicles, the problem is the motion on a soft or uneven surface, because the pressure of the wheel to the surface is relatively high. To get a lower pressure to the surface, several types of creeping mechanisms are used. For motion on an uneven surface the best solution may be using of ledged mechanisms. In some cases also wheeled vehicles can be used on an uneven surface if a special construction of a vehicle and special driving wheels will be used (Fig. 2.35).

Figure 2.35 Example of a vehicle for moving on an uneven surface

Control of creeping machines In the case of machines using a creeping driving mechanism, the brakes are used to control the turning. If turning is needed the inner to curve creeper must be broken. Normally this creeper will be decoupled from the drive. Brakes are used for turning by some special wheeled vehicles, e.g. construction or loading machines when the motion distances are relatively small. Machines the turning of which is controlled by brakes are shown in Fig. 2.36. Sometimes turning with brakes is also useful for robots.

65

Figure 2.36 Machines using a crawling driving mechanism and brakes for turning (Photos of Uwe Berg from Internet)

Walking robots or ledged robots Walking or ledged robots are copied from nature. Depending on the number of legs, walking robots can be divided as follows:

• One-leg robots • Two-leg robots • Three-leg robots • Four-leg robots • Six-leg robots • Eight-leg robots • Multi-leg robots (hundred-leg robots)

If one- or two-leg robots are used, an additional problem of keeping balance appears. Generally to control balance of a robot, dynamic feedback from acceleration sensors is needed. Three-leg robots are used seldom because the same problem to keep balance if the third leg is moved exist. Mainly three-leg robots are useful for climbing.

Phases of motion of a two-leg walking mechanism are shown in Fig. 2.37.

1 2 3 4

I II II I II I II I

Figure 2.37 Phases of motion of a two-leg walking mechanism

Walking starts if the weight of a body is transferred to the stretched leg (II) and free leg movement in the direction of motion. In the second phase of walking, leg (I) is in its final forward position. In the third phase of walking, this leg will be put to ground. In the fourth phase of walking, the weight of a body will be transferred to leg (I). These phases will be repeated cyclically and the free leg (II) will be moved in the direction of walking motion.

66 Two- and four-leg human or animal kind robots are shown in Fig. 2.38.

a b c

Figure 2.38 Examples of two- and four-leg human or animal kind robots: Two-leg (bipod) robot Asimo from firm Honda Co (a) and four-leg (quadruped, tetrapod) Robodog from RoboScience (b, c)

The walking mechanisms of a four-leg and six-leg robot are shown in Fig. 2.39.

Figure 2.39. Walking mechanisms of a four- and six-leg robot

The higher number of legs gives more stability to the vehicle and more possibilities to move on an uneven surface. An eight-leg robot is very similar to a six-leg robot. Robots having more than eight legs are used seldom, only in special cases. Motion of these robots is more similar to the moving of creepers than to a walking human or animal. A ten-leg robot that moves by turning pairs of legs is shown in Fig. 2.40.

Sometimes it may be useful to combine wheels and legs in a robot’s motion mechanism. In this case the robot is named a wheeled and ledged hybrid robot.

67

Figure 2.40 Ten-leg robot that moves by the turning pairs of legs

Hybrid vehicles using legs and wheels Legs give more possibilities to overcome obstacles but wheels have a simpler construction and the motion is more efficient. Examples of hybrid robots are shown in Fig. 2.41.

Figure 2.41 Hybrid vehicles using legs and wheels

Three-leg climbing robot. The kinematics of a three-leg climbing robot is shown in Fig. 2.42. Two legs of the robot are used for holding and the third leg moves to the new place of holding. Legs move using the chain of leg links coupled by the revolute kinematics pairs.

Holding place 3 Free leg 3

Kinematics chain

Pelvis of legs

Holding leg 1 Holding leg 2

Figure 2.42 Climbing mechanism

68