Automatic design of control systems for robot ... - Semantic Scholar

1 downloads 0 Views 878KB Size Report
In 50 independent optimization trials, the PID controllers designed using the ... inverse modelling trials. ...... as part of the Objective 1 SUPERMAN project, the.
1

Automatic design of control systems for robot manipulators using the bees algorithm A A Fahmy1*, M Kalyoncu2, and M Castellani3 1

Cardiff School of Engineering, Cardiff University, Cardiff, UK

2

Department of Mechanical Engineering, University of Selcxuk, Konya, Turkey

3

Department of Biology, University of Bergen, Bergen, Norway

The manuscript was received on 10 June 2011 and was accepted after revision for publication on 12 September 2011. DOI: 10.1177/0959651811425312

Abstract: This paper proves the capability of the bees algorithm to solve complex parameter optimization problems for robot manipulator control. Two applications are presented. The first case considers the modelling of the inverse kinematics of an articulated robot arm using neural networks. The weights of the connections between the nodes need to be set so as to minimize the difference between the neural network model and the desired behaviour. In the proposed example, the bees algorithm is used to train three multilayer perceptrons to learn the inverse kinematics of the joints of a three-link manipulator. The second case considers the design of a hierarchical proportional–integral–derivative (PID) controller for a flexible singlelink robot manipulator. The six gains of the PID controller need to be optimized so as to minimize positional inaccuracies and vibrations. Experimental tests demonstrated the validity of the proposed approach. In the first case, the bees algorithm proved very effective at optimizing the neural network models. Compared with the results obtained employing the standard back-propagation rule and an evolutionary algorithm, the bees algorithm obtained superior results in terms of training accuracy and robustness. In the second case, the proposed method demonstrated remarkable efficiency and consistency in the tuning of the PID controller parameters. In 50 independent optimization trials, the PID controllers designed using the bees algorithm consistently outperformed a robot controller designed using a standard manual technique. Keywords: bees algorithm, robot control, optimization, inverse kinematics modelling, neural networks, hierarchical proportional–integral–derivative robot control

1

INTRODUCTION

Robotic manipulators are usually composed of a multi-link ‘arm’ and an end effector. The desired position of the end effector is achieved through the control of the angles of the robot joints. A multi-link robot manipulator can be regarded as a multi-input multi-output (MIMO) system. Conventional control methods for MIMO systems require the exact

1

*Corresponding author: Institute of Mechanical and Manufacturing Engineering, Cardiff School of Engineering, Cardiff University, Queen’s Building, The Parade, Cardiff CF24 3AA, UK. email:[email protected]

knowledge of the plant mathematical model. For robot manipulators, it is almost impossible to identify precisely the system model and its parameters. For this reason, a popular solution for the control of multi-link robotic arms is to use approximate inverse model control techniques. The inverse kinematics of the robot joints are often modelled through parametric equations that are fitted to experimental input/output (end effector positions/ joint angles) data pairs. Alternatively, one-link robotic arms are employed. The main advantage of such manipulators is their inherent simplicity. One-link manipulators are usually controlled via proportional–integral–derivative (PID) methods [1–7]. The main challenge in this case Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

1 1 1

2

A A Fahmy, M Kalyoncu, and M Castellani

is to tune the controller parameters. Flexible-link robot manipulators are a special kind of one-link manipulators. The main advantage of using a flexible link is that it allows one to build lightweight robots capable of moving large payloads at high speeds and with high precision [8]. Unfortunately, the dynamics of flexible-link manipulators are far more complex than those of rigid manipulators [9–16] and this makes the tuning of the PID controller difficult. Approximate inverse model and PID algorithms are two popular solutions to the problem of controlling robotic end effectors in industrial applications. They are instances of the two possible approaches to Cartesian manipulator positioning and control, respectively model-based and model-free control. Both approaches entail a parameter optimization task. In the case of a one-link robot arm, the optimal PID parameters are to be found. In the case of a multi-link robot arm, the inverse model parameters need to be fitted (i.e. optimized) to the experimental data. The present paper investigates the application of the bees algorithm to solve these two parameter optimization tasks. The aim of the work is to demonstrate the effectiveness of the bees algorithm as a tool for the optimization of complex robot control systems, including both model-based and model-free approaches. A three-link robot manipulator is first considered. The inverse kinematics of the robot joints are modelled using three multilayer perceptron (MLP) neural networks (NNs) [17]. Each NN is trained to reproduce the inverse kinematics of one of the three manipulator joints from a set of input/output data pairs. The bees algorithm is used to train the three NNs [18, 19]. The MLP training results obtained using the proposed algorithm are compared with the training results obtained using the standard back-propagation (BP) rule [17] and an evolutionary algorithm (EA) [20]. The optimization of a hierarchical PID controller for a flexible-link robot is then considered. The bees algorithm is employed to optimize the six gains of the hierarchical PID controller in order to achieve maximum link position accuracy with minimum vibration. The results obtained using the bees algorithm are compared with the results obtained using a manual tuning technique based on trial and error [21]. The paper is organized as follows. Section 2 describes the NN modelling of the inverse three-link manipulator kinematics. Section 3 outlines the three MLP training algorithms used in the approximate inverse modelling trials. Section 4 presents the results of the inverse modelling trials. Section 5 describes the hierarchical PID robotic link controller Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

and presents the optimization results. Section 6 concludes the paper.

2

MODELLING THE INVERSE KINEMATICS OF A THREE-LINK MANIPULATOR

A robotic arm manipulator represents a very complex and non-linear system. Parameter variations, different arm configurations, un-modelled friction, and backlashes usually make it difficult to identify precisely the forward and inverse dynamics and the inverse kinematics of the robot system. Given a general MIMO system with input u = fu1 ; . . . , un g and output y = fy1 , . . . yn g, and a discrete time sampling, the system output at time interval k can be expressed as follows y(k) = f (y(k  1), . . . , y(k  n), u(k  1), . . . , u(k  m))

ð1Þ

where m\k and n\k are discrete time intervals. Given a set of input/output data samples, the goal of the model identification task is to express the non-linear input/output relationship f, and the n and m time constants. If n and m are given, the only task is to identify the function f. For time-invariant systems, f does not change with time. Since a robot manipulators can be regarded as bounded-input bounded-output stable system, equation (1) can be used to obtain the inverse model. For trajectory tracking purposes, the inverse kinematic model of an articulated robot arm can be expressed for each joint angle in the following approximate format ui (k) ffi f ðx(k), y(k), z(k), u1 (k  1), u2 (k  1), un (k  1)Þ

ð2Þ

where k is the sampling interval, i = ð1, 2, nÞ is the manipulator link, (x, y, z) is the end effectors’ Cartesian position, n is the number of joints, and ui is the ith joint angle. In this study, a three-link robot arm is considered. In this case, the inverse kinematic model corresponds to a six-input threeoutput functional mapping. This three-output system can be decomposed into three single-output systems. In order to control the position of the end effector in a Cartesian reference space, each of the three joint functions needs to be identified. The MLP is known to be capable to approximate with arbitrary precision any complex non-linear functional relationship [22]. The non-linear mapping capability makes this type of NN an ideal

2

Automatic design of control systems for robot manipulators using the bees algorithm

candidate to model functions of the kind of equation (1) [23, 24]. The MLP is characterized by a feedforward processing architecture; that is, each unit takes as input the weighted sum of the outputs of the nodes of the previous layer. The input layer is composed of a number of units equal to the number of input variables, and usually acts as a buffer. One or more layers of non-linear processing nodes are cascaded (hidden layers). The non-linear functional mapping of the hidden layer elements is usually implemented through the hyperbolic tangent function. The output layer is composed of a number of elements that is equal to the number of output variables. Each output layer node takes as input the weighted sum of the output of the last hidden layer units. This sum is mapped to the node output via the sigmoidal function. The mapping of an MLP can be modified by changing the weights of the connections between the units. In this way, the NN can be brought (trained) to reproduce any desired function. NN training is performed through inductive learning procedures. A set of input/output data pairs is sampled from the desired function and the connection weights are tuned so as to fit the NN response to the training data. MLP training is essentially a parameter learning procedure, where the goal is to minimize the error between the NN response and the desired output. In the case of the proposed three-joint manipulator, one MLP was trained to model the inverse kinematics for the each of the three robot joints. For each robot joint, 13 580 input/output data pairs of end effector positions/ joint angles were generated from the robot arm model. Each joint angle ui ranged in the interval {30°, 330°}. Eighty per cent of the data pairs (training set) were randomly picked to train the MLPs to reproduce the inverse kinematics of the robot joints, the remaining 20 per cent (test set) was used for model validation. 3

MLP WEIGHT TRAINING ALGORITHMS

Customarily, MLPs are trained using the BP algorithm [23]. This procedure modifies the NN weights based on gradient descent of the error landscape [17, 23]. Unfortunately, due to the high complexity and multimodal nature of the MLP error surface, greedy search techniques like the BP rule are prone to get stuck into flat regions and local error minima. Global population-based search techniques such as EAs [20] produce more reliable results when searching complex and multimodal solution spaces. In this

3

study, the bees algorithm is used to train the MLPs and its performance is compared with that of BP and an EA. 3.1 Back-propagation rule The MLP was trained using the BP rule with momentum term [17, 23]. The learning procedure was run for a fixed number of iterations on the training set of examples. The results of the learning trials were used as a baseline for assessing the efficacy of the more complex population-based algorithms. 3.2 Evolutionary algorithm The flowchart of the EA is shown in Fig. 1. Fitness ranking with elitism [20] was used to select the reproducing individuals. At each learning cycle, a new population was produced through mutation and BP of the reproducing individuals. New solutions replaced old ones via generational replacement [20]. The procedure was repeated until a predefined number of iterations had elapsed and the fittest solution of the last generation was picked. Genetic mutations slightly modified the weights of the nodes of a solution. For each weight, the perturbation was randomly sampled with uniform probability from an interval of predefined width. The BP rule was introduced as a deterministic mutation operator with the purpose of speeding up the learning process. Because of the real-valued encoding of the weight settings and the lack of genetic crossover, the weight optimization procedure was conceptually akin to evolutionary programming [20]. This paradigm allows the candidate solutions to be represented in a compact format and avoids the problems stemming from the use of crossover [20, 25]. 3.3 Bees algorithm The flowchart of the bees algorithm is given in Fig. 2. The bees algorithm mimics the foraging behaviour of honey bees [26]. At the start of the procedure, n scout bees are randomly distributed with uniform probability across the environment (i.e. the solution space). Each bee evaluates the fitness of the site (i.e. solution) where it landed. The main bees algorithm procedure consists of the following sequence of steps. The sites discovered by the scouts are ranked in decreasing order of fitness. The fittest m locations (best) are selected for the local search phase. In the local search phase, the neighbourhood of the selected sites is further searched. That is, the scouts Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

4

A A Fahmy, M Kalyoncu, and M Castellani

Fig. 1 Flowchart of the EA

Random Initialisation

Waggle dance Local Search

Elite patches (ne) nre bees per patch

Best patches (nb-ne) nrb bees per patch

Fitness evaluation

Fitness evaluation

Select fittest of each patch

Select fittest of each patch

Global Search Update Population

Random ns-ne Fitness Evaluation

no

stop? yes

Solution Fig. 2 Flowchart of the bees algorithm

that found the top (elite) e < m sites recruit each nep ‘forager’ bees. The scouts that landed on the remaining m  e selected locations recruit each nsp < nep foragers. The recruiting procedure

Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

simulates the mechanism of the waggle dance [27] in nature. Each forager is placed within a square of side ngh centred on the selected location. If a forager lands in a position of higher fitness than the

Automatic design of control systems for robot manipulators using the bees algorithm

scout, that forager becomes the new scout and will compete to recruit bees for further local exploration in the next iteration. If no forager finds a candidate solution of higher fitness than the scout, the size of the neighbourhood is shrunk (neighbourhood shrinking procedure). The purpose of the neighbourhood shrinking procedure is to make the search increasingly focused around the selected sites. If the local search procedure fails to bring any improvement of fitness for a given number lim of iterations, the search is deemed to have found a local peak of performance and the scout is randomly re-initialized (site abandonment procedure). If the location being abandoned is the fittest so far, it is stored in memory. If no better solution is found during the remainder of the search, the saved best fitness location is taken as the final solution. The global search phase follows. In this phase, n  nb scout bees are randomly placed on the solution space. The aim of the global search procedure is to look for new areas of high fitness. At the end of one cycle of the bees algorithm, the m scouts resulting from the local search procedure and the n  m scouts resulting from the global search procedure are kept for the next iteration. For a more detailed description of the bees algorithm, the reader is referred to reference [28]. 4

5

Table 1 Parameter settings for the different algorithms MLP settings Input nodes Output nodes Hidden layers Hidden nodes Activation function of hidden nodes Activation function of output nodes

6 1 2 5 per layer Hyper-tangent Sigmoidal

Learning algorithms settings

BP

EA

Learning coefficient Momentum term Initial range for MLP weights Trials Generations Population size MLP weights mutation rate Amplitude MLP weights mutation Back-propagation mutation rate

0.1 0.01 [–0.05, 0.05] 10 50 000 n.a. n.a. n.a. n.a.

n.a. n.a. [–0.05, 0.05] 10 10 000 100 0.3 0.1 0.4

n.a., not applicable.

Table 2 Parameter settings for the bees algorithm

Learning cycles Scout bees Elite sites Best sites Recruited elite Recruited best Neighbourhood Stagnation limit

Symbol

Value

lc n e m nep nsp ngh lim

50 000 15 2 13 50 20 0.2 5

NEURAL NETWORK TRAINING RESULTS

To simplify the training of the individuals, input data were normalized according to the mean-variance procedure. A sampling procedure was used to reduce the computational overheads and the running time of the algorithms. The method randomly selected a subset of the training set, at each learning cycle, and used this sample instead of the full training set. The size of the subset was 5 per cent of the training examples. The large number of instances guarantees a sufficient representativeness of the sampled subsets. The structure of the MLPs was optimized by trial and error. The MLP training results obtained using the bees algorithm were compared with those obtained using the BP rule and an EA. Each algorithm was run for a number of cycles that was sufficient for it to converge (i.e. the learning curve becomes flat). The modelling accuracy (root-mean-square (r.m.s.) error) of the trained MLP was estimated on the test set of examples. This procedure was repeated ten times with different random initializations. The modelling accuracy of each algorithm was estimated as the average test accuracy of the

ten MLPs solutions. Table 1 describes the MLP structure, and the parameter settings for the BP algorithm and the EA, while Table 2 lists the parameter settings for the bees algorithm. Figure 3 shows the MLP predictions (i.e. the MLP outputs) of the joint-1 angle positions u1(t + 1) (measured in degrees) for the 2715 input data samples, i.e. end effector positions x1,2,3(t + 1) and current angle positions u1,2,3(t), of the test set. The actual joint angle positions are included in the plot for reference. The plot refers to the MLP trained using the bees algorithm. Table 3 compares the accuracy results obtained using the bees algorithm with the results obtained using BP and the EA for the prediction of joint-1 angle. For each algorithm, Table 3 reports the average r.m.s. accuracy m of ten independent learning trials, the standard deviation s of the learning results, and gives the upper and lower bounds of the 95 per cent confidence interval. The statistical significance of the differences between the results obtained by the bees algorithm and the results obtained using BP and the EA is evaluated using Student’s t-tests. For each comparison, Table 3 contrasts the critical value for a 5 per cent Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

6

A A Fahmy, M Kalyoncu, and M Castellani

330

Table 4 Joint-2 accuracy and t-test results for the different algorithms

modelling results - joint angle 1

degrees

280

Accuracy results

Bees algorithm

BP

EA

m s Upper bound Lower bound

1.7785 0.0708 1.8291 1.7279

1.9250 0.1651 2.0432 1.8069

1.7961 0.0413 1.8256 1.7666

Bees algorithm – BP

Bees algorithm – EA

2.2622 2.579294

2.2622 0.678771

230 180 actual model

130

t-Test results 80 sample 30 0

250 500 750 1000 1250 1500 1750 2000 2250 2500

t(0.025) t-Test statistic

– –

Fig. 3 Modelling results for joint-1 angle modelling results - joint angle 3

degrees 330

Table 3 Joint-1 accuracy and t-test results for the different algorithms Accuracy results m s Upper bound Lower bound

Bees algorithm

BP

EA

1.3210 0.0511 1.3575 1.2844

1.5059 0.0623 1.5505 1.4613

1.4504 0.0665 1.4980 1.4028

Bees algorithm – BP

Bees algorithm – EA

2.2622 7.260704

2.2622 4.88306

280 230 180

actual model

130 80

sample

t-Test results t(0.025) t-Test statistic

– –

modelling results - joint angle 2

degrees 330 280 230 180

actual model

130 80

sample 30 0

250

500

750 1000 1250 1500 1750 2000 2250 2500

Fig. 4 Modelling results for joint-2 angle

level of significance t(0.025) with the t-test statistics. Table 3 confirms that for joint-1 angle prediction task, the results produced by the bees algorithm are statistically significantly better than the results produced by the BP algorithm and the EA. Figure 4 shows the actual joint angle position (degrees) and the MLP model predictions (degrees) for the 2715 data samples of the test set for joint-2 Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

30 0

250

500

750 1000 1250 1500 1750 2000 2250 2500

Fig. 5 Modelling results for joint-3 angle

angle, u2. The plot refers to the MLP trained using the bees algorithm. Table 4 compares the accuracy results obtained using the bees algorithm with those obtained using BP and the EA for joint-2 angle. The statistical significance between the results of the three algorithms is evaluated using Student’s t-tests. Table 4 shows that for joint-2 angle prediction task, the results produced by the bees algorithm are statistically significantly better than the results produced using BP. For the joint-2 angle prediction task, the bees algorithm and the EA obtained results that are statistically comparable. Figure 5 plots the actual joint angle position (degrees) and the MLP model predictions (degrees) for the 2715 data samples of the test set for joint-3 angle, u3. The plot refers to the MLP trained using the bees algorithm. Table 5 compares the accuracy results obtained using the bees algorithm with those obtained using BP and the EA for joint-3 angle. The statistical significance between the results of the three algorithms is evaluated through Student’s t-tests. Table 5 shows that for joint-3 angle prediction task, there are no statistically significant differences between the results produced by the three

Automatic design of control systems for robot manipulators using the bees algorithm

7

Table 5 Joint-3 accuracy and t-test results for the different algorithms Accuracy results

Bees algorithm

BP

EA

m s Upper bound Lower bound

3.1529 0.1104 3.2318 3.0739

3.1993 0.1466 3.3041 3.0944

3.1736 0.1162 3.2567 3.0905

Bees algorithm – BP

Bees algorithm – EA

2.2622 0.799987

2.2622 0.409388

t-Test results t(0.025) t-Test statistic

– –

Fig. 6 Schematic diagram of the flexible-link robot manipulator

algorithms. In general, Figs 3 to 5 show that the bees algorithm finds it most difficult to model the robot kinematics at the extremes of the angle span (30° and 330°) of the three joints. This is a common problem for all of the algorithms, and is due to the steep non-linearity at the transition boundaries. 5

PID CONTROLLER DESIGN FOR FLEXIBLELINK MANIPULATOR

A schematic diagram of the flexible-link robot manipulator is given in Fig. 6. The mass and elastic properties of the link are assumed to be distributed uniformly along the link. The flexible link is taken to be an Euler–Bernoulli beam. u represents the angular position of the equivalent rigid link with respect to the fixed frame XY. D represents position of the tip with respect to the equivalent rigid link. Assuming small deflections of the link, an approximate linear time-invariant dynamic model is derived using Lagrangian formulation and the dynamic equation is represented in matrix form as ð3Þ

where q is the vector of generalized coordinates, q = ½u, aT , M is the mass matrix, C is the damping matrix, K is the stiffness matrix, and F = ½ T 0 T . T is the input torque applied at the joint. The variable a (=D/L) represents the slope at the free end of the flexible link. The dynamic model can be represented in statespace form as x = A x_ + B u ð4Þ

y =Cx  where x = u a C are given by

u_

a_

T

0232 A= M1 K  B=

0231 M1

I232 M1 C





ð5Þ

C = I234

5.1 Hierarchical PID controller

Mq€ + Cq_ + Kq = F



and the matrices A, B, and

A closed-loop block diagram of the proposed hierarchical PID control system is illustrated in Fig. 7. The controller has two subsystems. The ‘fast’ subsystem reduces the vibrations of the manipulator tip, and the ‘slow’ subsystem controls the attainment of the desired position. The hierarchical PID controller has six gains which need to be tuned. As can be seen in Fig. 7, in the hierarchical PID controller, the error signal e(t) and tip deflection a(t) are employed to generate proportional, integral, and derivative actions. The resulting signals are summed to form the control signal u(t) that is applied to the plant model. The mathematical description of the hierarchical PID controller is u(t) = KPslow . eu (t) + KIslow . + KPfast . a(t) + KIfast .

ðt 0

ðt 0

eu (t)dt + KDslow .

a(t)dt + KDfast .

da(t) dt

deu (t) dt ð6Þ

where u(t) is the input signal to the plant model, and KP, KI, and KD are the proportional, integral, and derivative gains of the hierarchical PID controllers, respectively. The error signal eu(t) is defined as eu ðtÞ = rðtÞ  uðtÞ, and r(t) is the desired input signal. In order to achieve high performance control of the robotic arm, the hierarchical PID controller gains must be trained to achieve the best transient response of the robot. That is, the parameters (gains) of the hierarchical PID controller must be adjusted to optimize the robot transient response. Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

8

A A Fahmy, M Kalyoncu, and M Castellani

Actual Rotation

u(t) Desired Rotation

+_

+

Slow PID controller

Robot Manipulator

+

Tip Deflection Fast PID controller

Fig. 7 Block diagram of the hierarchical PID controller

Table 6 Parameter settings for the bees algorithm

Learning cycles Scout bees Elite sites Best sites Recruited elite Recruited best neighbourhood Stagnation limit

Symbol

Value

lc n e m nep nsp ngh lim

1000 20 3 10 20 10 0.001 not used

Fig. 8 Schematic diagram of the control system

Table 7 Gains of the manually tuned hierarchical PID controller KPslow

KIslow

KDslow

KPfast

KIfast

KDfast

15

0.3

5

1.5

0.3

1

In this paper, the bees algorithm was applied for tuning the hierarchical PID controller gains. The bees algorithm was programmed using MATLAB and run on an Intel P4 2.4 GHz personal computer with 1.0 GB memory. 5.2 Hierarchical PID controller experimental results The aim of this experiment was to test the hierarchical PID controller gains tuned using the bees algorithm and to assess the response of the system. The parameters of the bees algorithm were set as in Table 6. The effectiveness of the proposed technique was compared with that of a trial-and-error technique [21]. The PID gains of the manually tuned controller are given in Table 7. The results obtained by the bees algorithm were tested on a physical flexible single-link robot manipulator. A schematic diagram of the experimental system is given in Fig. 8. The components of the manipulator are shown in Fig. 9. The flexible link is a thin aluminium beam with strain gauges mounted on its base. The gauges were calibrated to produce 1 V per 25 mm of tip deflection. The flexible link was fixed at one end to

Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

Fig. 9 Photograph of the single flexible-link robot manipulator experiment

Table 8 Physical and geometric characteristics of the flexible robot manipulator Parameter

Symbol

Value

Unit

Motor inertia Flexible link length Flexible link height Flexible link thickness Flexible link linear density Flexible link flexural rigidity

Jh L h d r EI

0.0020 0.4500 0.0200 0.0008 0.1333 0.1621

kgm2 m m m kg/m Nm2

the shaft of the d.c. servo motor. The motor was a voltage-driven Quanser SRV02-ET model equipped with angular speed and position sensors. Interaction with the controlled plant was provided by a Quanser UPM 2405 power module and a Quanser MultiQ PCI interface card. The WinCon software developed by Quanser allowed communication with SIMULINK. This made MATLAB control possible.

Automatic design of control systems for robot manipulators using the bees algorithm

Table 9 Values of the weight factors w1

w2

w3

w4

w5

w6

1.0

1.0

1.0

500.0

500.0

150.0

The sampling rate was 100 Hz. The angular speed sensor is a tachometer calibrated to produce 1.5 mV per r/min, with a measurement range of 6 5 volt. The angular position sensor is an optic encoder of 0.08789 degree/count resolution. The physical parameters of the flexible arm are given in Table 8. Substituting these parameters into the dynamic model equation (5), the state-space form of the manipulator can be obtained as 8 9 2 0 0 > u_ > > = 6 < > 0 0 a_ =6 4 0 566:46 € > > u > ; : > 0 921:77 a € 2 3 0 6 0 7 7 +6 4 65:11 5Vm 65:11

1 0 37:02 37:02

38 9 0 > u> > = < > 17 a 7 5 _ 0 > u> > ; : > a_ 0

ð7Þ

where Vm is the servomotor voltage. The objective function of the controller system is J = w1  td + w2  tr + w3  tp + w4  M + w5  ess + w6  jAa jmax

ð8Þ

where wi are weight factors, td is the delay time, tr the rise time, tp the peak time, M the maximum overshoot, ess the steady-state error, and Aa the amplitude of the tip deflection. The weight factors were chosen by trial and error, with the aim of minimizing in particular the maximum overshoot, the steady-state error, and the amplitude of the tip deflection. For this reason, w4 to w6 are much larger w1 to w3. The weight vectors are given in Table 9. In the tests, the bees algorithm was used to optimize the gains of the hierarchical PID controller using the dynamic model of the single flexible-link robot manipulator. Equations (7) and (8) were employed to evaluate the candidate solutions for the gains of the hierarchical PID controller. Subsequently, the gains optimized using the bees algorithm were used on the experimental setup. The PID gains obtained for 50 independent runs of the bees algorithm are given in Table 10, which shows that the bees algorithm was able to produce several different solutions for the PID gains without significant variation of the controller performance.

9

If needed, the bees algorithm can be used to generate a set of candidate solutions from which the final configuration is chosen according to specific parameters like delay time, rise time, peak time, maximum overshoot, steady-state error, or servo motor control voltage. For the control of the physical manipulator, the gains obtained by the bees algorithm and the gains obtained using a trial-and-error technique [21] were tested. The desired input signal for the rotation of the robot manipulator was assumed to be a step function and its final value was defined as 450. While the robot arm moved, the deflection of the tip of the arm must be close to zero degrees. Figures 10, 11, and 12 show the results obtained by the bees algorithm and the trial-and-error technique [21] for angular displacement, tip deflection, and servo motor voltage, respectively, where the results of 50 trials of the bees algorithm are presented. Figure 10 shows that with the bees algorithm, the flexible arm can move faster and more reliably compared with the trial-and-error technique. Figure 11 shows that the gains optimized using the bees algorithm produced less tip vibration than the trial-anderror technique. The servo motor voltages for the each PID controller are given in Fig. 12. The controllers tuned by the bees algorithm have smaller and smoother control voltages than those from the trialand-error technique. The objective function value (the cost) was given in reference [21] as 28.1728. However, the mean objective value for 50 different runs of the bees algorithm was found to be 19.9496. The standard deviation of the mean objective value over the 50 runs was extremely modest (0.4540), which proves the reliability of the proposed algorithm. The similarity of the action of the 50 controllers generated using the bees algorithm (see Figs 10 to 12), and the small standard deviation (0.4540) of their fitness, suggest that the PID gains obtained using the proposed technique might possess a certain degree of robustness. Further tests are needed to investigate in full the robustness of the gain settings generated using the proposed approach. 6

CONCLUSIONS

The bees algorithm was applied to two parameter optimization tasks for robot manipulator control. In the first application, the proposed algorithm was used to train three MLPs to model the inverse kinematics of the joints of a three-link robot manipulator. The bees algorithm produced accurate learning results for all three robot joints. The small standard Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

10

A A Fahmy, M Kalyoncu, and M Castellani

Table 10 Gains of the hierarchical PID controller KPslow 3.4328 2.9499 3.6515 2.8780 3.0043 2.9981 3.5035 2.4705 3.5579 3.9323 4.3788 3.0381 3.2396 3.8278 3.2910 2.4631 3.3721 2.7124 3.2886 2.4415 3.7824 4.2696 2.2401 3.6077 3.1341 2.9195 3.4879 2.1517 3.3709 2.9115 2.6287 3.0609 2.4636 3.0576 2.8340 3.4065 3.1189 3.0177 2.0993 3.7401 3.3526 2.6721 2.1679 3.2850 2.7752 3.0769 3.3241 2.6643 2.5718 2.7107

0.0136 0.0056 0.0203 0.0152 0.0348 0.0410 0.0385 0.0489 0.0473 0.0139 0.0074 0.0647 0.0305 0.0139 0.0500 0.0620 0.0251 0.0578 0.0120 0.0544 0.0239 0.0035 0.0605 0.0112 0.0467 0.0609 0.0227 0.0465 0.0166 0.0267 0.0263 0.0058 0.0521 0.0295 0.0329 0.0455 0.0390 0.0399 0.0598 0.0053 0.0182 0.0447 0.0395 0.0279 0.0509 0.0176 0.0282 0.0388 0.0287 0.0317

KDslow

KPfast

KIfast

KDfast

Objective function value

0.0720 0.0161 0.1211 0.0361 0.0530 0.0577 0.1190 0.0056 0.1380 0.1795 0.2459 0.0405 0.1099 0.1472 0.1164 0.0202 0.1362 0.0665 0.0805 0.0285 0.1702 0.2398 0.0198 0.1236 0.0909 0.0714 0.1111 0.0030 0.0925 0.0763 0.0376 0.0694 0.0214 0.1000 0.0719 0.1595 0.1086 0.1035 0.0144 0.1632 0.1131 0.0857 0.0192 0.1592 0.0942 0.0695 0.1521 0.0675 0.0516 0.0752

0.9267 1.0979 2.0011 2.4329 1.8776 1.9132 1.8222 2.1121 2.6309 0.8994 2.5094 0.9444 1.9392 2.0840 2.6633 1.7357 2.3506 2.5311 0.6356 1.5641 2.8797 2.3625 2.7264 1.5708 2.0906 1.7511 1.3257 1.5672 0.8405 1.2529 0.5023 0.6214 1.1489 1.8292 1.4442 2.9080 1.7319 1.9452 2.8715 2.6807 1.5447 2.4468 1.9365 2.9627 1.9871 0.0664 2.6250 1.2395 1.0142 1.1337

1.8118 1.9091 0.8435 0.7321 1.4455 1.5068 0.5259 1.7794 0.7133 0.0395 0.4620 1.9592 0.1321 0.7567 1.9009 1.0255 0.6013 1.4809 1.8767 0.9396 1.0815 0.4601 0.4912 0.1302 1.6241 0.2117 1.6670 0.1562 0.3341 0.8690 0.8077 1.1792 1.1611 1.6901 1.9461 1.8314 0.1946 0.6688 0.4070 0.3583 0.9023 1.9907 1.5074 0.7317 0.6650 1.7933 1.7178 0.7508 1.6965 0.0488

0.1216 0.1337 0.0564 0.1143 0.0798 0.0644 0.0507 0.0764 0.0645 0.1402 0.1378 0.1374 0.0167 0.1038 0.0744 0.0296 0.0034 0.0515 0.0496 0.0061 0.0547 0.1310 0.0905 0.1056 0.1340 0.1336 0.1416 0.0051 0.0794 0.0393 0.0179 0.0442 0.1445 0.0642 0.0577 0.1486 0.1355 0.1340 0.1475 0.0840 0.1389 0.0547 0.0016 0.0811 0.1350 0.1484 0.1269 0.1227 0.0452 0.0635

20.1852 20.2222 20.6036 20.1648 20.0836 20.0940 20.5660 19.9595 20.3388 20.4545 20.0509 20.5942 19.5888 19.7904 20.0048 20.7782 19.6221 19.8780 19.8658 20.4916 20.1677 20.0823 19.7027 19.7263 19.6428 20.2247 19.7654 19.7168 20.2140 19.3300 19.4398 19.0987 19.5481 19.5712 19.2677 19.7119 19.4921 19.3283 19.5703 19.5611 19.3305 19.3106 19.2411 19.2291 19.6332 19.3373 19.0859 19.2567 19.1044 19.2274

Fig. 10 Angular displacement control Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

Fig. 11 Tip deflection control

Automatic design of control systems for robot manipulators using the bees algorithm

11

control problem. In this case, a new objective function will have to be defined.

FUNDING This research received no specific grant from any funding agency in the public, commercial, or notfor-profit sectors.

3

ACKNOWLEDGEMENT Fig. 12 Servo motor control voltages of the controllers

deviation calculated on ten independent learning trials proved the high reliability of the proposed technique. The results obtained by the bees algorithm were compared with those obtained using the BP algorithm and an EA. In contrast to the BP rule, the bees algorithm produces better learning results on the modelling of two out of three robot joints, and comparable learning results on the modelling of the remaining joint. Compared with the EA, the bees algorithm attains superior learning results on the modelling of one of the robot joints, and comparable learning results on the modelling of the remaining two joints. Overall, the standard deviation of the learning results produced by the two population-based algorithms is smaller than the standard deviation of the learning results produced by the BP algorithm. This result confirms the better reliability of global population-based optimization algorithms compared with greedy steepest descent search. In the second application, the proposed algorithm was applied to tune the gains of a hierarchical PID controller for a flexible single-link robot manipulator with a distributed mass. The aim of the control action was to bring the free end of the robot manipulator to a desired position and minimize arm vibrations while in motion. The controller was composed of two modules, a fast subsystem and a slow subsystem. The fast subsystem reduced the vibrations of the manipulator, and the slow subsystem controlled the attainment of the desired position. The six gains of the hierarchical PID controller were tuned using the bees algorithm to minimize vibrations and positioning errors. Experimental results show that the hierarchical PID controller parameters tuned using the bees algorithm are efficient and robust. The proposed investigation addressed the problem of regulation control of the flexible-link manipulator. Further work should address the tracking

The research described in this paper was performed as part of the Objective 1 SUPERMAN project, the EPSRC Innovative Manufacturing Research Centre Project, the EC FP6 Innovative Production Machines and Systems (I*PROMS) Network of Excellence, _ ¨ BITAK and TU (The Scientific and Technological Research Council of Turkey). Ó Authors 2011

REFERENCES 1 Homaifar, A., Bikdash, M., and Gopalan, V. Design using genetic algorithms of hierarchical hybrid fuzzy–PID controllers of two-link robotic arms. J. Robot. Syst., 1997, 14(6), 449–463. 2 Li, C. and Lian, J. The application of immune genetic algorithm in PID parameter optimization for level control system. In Proceedings of the IEEE International Conference on Automation and Logistics, Jinan, China, 18–21 August 2007, pp. 782–786. 3 Meng, X. and Song, B. Fast genetic algorithms used for PID parameter optimization. In Proceedings of the IEEE International Conference on Automation and Logistics, Jinan, China, 18–21 August 2007, pp. 2144–2148. 4 Cheong, J. and Lee, S. Linear PID composite controller and its tuning for flexible link robots. J. Vib. Contr., 2008, 14(3), 291–318. 5 Ho, M. T. and Tu, Y. W. PID controller design for a flexible-link manipulator. In Proceedings of the 44th IEEE Conference on Decision and Control, and the European Control Conference, Seville, Spain, 2005, pp. 6841–6846. 6 Lin, J. and Huang, Z. Z. Tuning the PID parameters for robot manipulators with compliant bases by using grey theory. In Proceedings of the 2006 IEEE International Conference on Control Applications, Munich, Germany, 2006, pp. 2522–2527. 7 Mansour, T., Konno, A., and Uchiyama, M. Modified PID control of a single-link flexible robot. Adv. Robot., 2008, 22(4), 433–449. 8 Cannon, H. Jr and Schmitz, E. Initial experiments on the end-point control of a flexible one-link robot. Int. J. Robot. Res., 1984, 3(3), 62–75. ˜ ez, V., and Sil9 Herna´ndez-Guzma´n, M., Santiba´n va-Ortigoza, R. A new tuning procedure for PID

Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

4

4

5

5

12

10

11

6 12

13 14

15

16

5 17 18

7

A A Fahmy, M Kalyoncu, and M Castellani

control of rigid robots. Adv. Robot., 2008, 22(9), 1007–1023. Kalyoncu, M. Mathematical modelling and dynamic response of a multi-straight-line path tracing flexible robot manipulator with rotating-prismatic joint. Appl. Math. Model., 2008, 32(6), 1087– 1098. Dwivedy, K. and Eberhard, P. Dynamic analysis of flexible manipulators, a literature review. Mech. Machine Theor., 2006, 41, 749–777. Monje, C. A., Ramos, F., Feliu, V., and Vinagre, B. M. Tip position control of a lightweight flexible manipulator using a fractional order controller. IET Contr. Theor. Applic., 2007, 1(5), 1451–1460. Sanz, A. and Etxebarria, V. Experimental control of a single-link flexible robot arm using energy shaping. Int. J. Syst. Sci., 2007, 38(1), 61–71. Karimi, H. R., Yazdanpanah, M. J., Patel, R. V., and Khorasani, K. Modelling and control of linear two-time scale systems: applied to single-link flexible manipulator. J. Intell. Robot. Syst. Theor. Applic., 2006, 45(3), 235–265. Lin, J. and Huang, Z. Z. A hierarchical fuzzy approach to supervisory control of robot manipulators with oscillatory bases. Mechatronics, 2007, 17(10), 589–600. Kalyoncu, M. and Tıınkıır, M. Mathematical model for simulation and control of nonlinear vibration of a single flexible link. In Proceedings of 5th International Symposium on Intelligent Manufacturing Systems (IMS’2006), Sakarya, Turkey, 2006, pp. 435–442. Pham, D. T. and Liu, X. Neural networks for identification, prediction and control, 1995 (SpringlerVerlag Ltd, London). Pham, D. T., Ghanbarzadeh, A., Koc, E., Otri, S., Rahim, S., and Zaidi, M. The bees algorithm, a novel tool for complex optimisation problems. In Proceedings of the 2nd International Virtual Conference on Intelligent production machines and systems (IPROMS 2006), 2006, pp. 454–459 (Elsevier, Oxford, UK).

Proc. IMechE Vol. 225 Part I: J. Systems and Control Engineering

19 Pham, D. T., Kocx, E., Ghanbarzadeh, A., and Otri, S. Optimisation of the weights of multilayered perceptrons using the bees algorithm. In Proceedings of the 5th International Symposium on Intelligent Manufacturing Systems (IMS’2006), Sakarya, Turkey, 2006, pp. 38–46. 20 Fogel, D. B. Evolutionary computation: Toward a new philosophy of machine intelligence, edition 2, 2000 (IEEE Press, New York, New York). 21 Kalyoncu, M. and Tıınkıır, M. Hierarchical adaptive network based fuzzy logic controller design for a single flexible link robot manipulator. In Proceedings of the 13th International Power Electronics and Motion Control Conference (EPE-PEMC 2008), Poznan´, Poland, 2008, pp. 989–996. 22 Hornik, K., Stinchcombe, M., and White, H. Multilayer feedforward networks are universal approximators. Neural Networks, 1989, 2, 359–366. 23 Lippmann, R. P. An introduction to computing with neural nets. IEEE ASSP Mag., 1987, 4–22. 24 Narendra, K. S. and Parthasarathy, K. Identification and control of dynamical systems using neural networks. IEEE Trans. Neural Networks, 1990, 1(1), 4–27. 25 Thierens, D., Suykens, J., Vanderwalle, J., and De Moor, B. Genetic weight optimisation of a feedforward neural network controller. In Artificial neural networks and genetic algorithms (Eds R. F. Albrecht, C. R. Reeves, and N. C. Steele), editors, 1993, pp. 658–663 (Springler-Verlag, Vienna). 26 Tereshko, V. and Loengarov, A. Collective decision-making in honey bee foraging dynamics. Comput. Inform. Syst. J., 2005, 9(3), 1–7. 27 Von Frisch, K. Bees: Their vision chemical senses language revised edition, 1976 (Cornell University Press, Ithaca, New York). 28 Pham, D. T. and Castellani, M. The bees algorithm – modelling foraging behaviour to solve continuous optimisation problems. Proc. IMechE, Part C: J. Mechanical Engineering Science, 2009, 223(12), 2919–2938.

5

5 6 8

Suggest Documents