Robotica (2012) volume 30, pp. 847–855. © Cambridge University Press 2011 doi:10.1017/S026357471100107X
Learning the forward kinematics behavior of a hybrid robot employing artificial neural networks Rongjie Kang†,∗, H´el`ene Chanal†, Thomas Bonnemains†, Sylvain Pateloup†, David T. Branson III‡ and Pascal Ray† † Laboratoire de M´ecanique et Ing´enieries, Institut Franc¸ais de M´ecanique Avanc´ee, Rue Roche Genes 27, 63175 Aubiere, France ‡ Department of Advanced Robotics, Istituto Italiano di Tecnologia, Via Morego 30, 16163 Genova, Italy (Accepted September 1, 2011. First published online: October 14, 2011)
SUMMARY Hybrid robots, composed of a parallel platform and serial wrist, achieve a compromise of stiffness and dexterity. Thus, they are well suited for applications such as aircraft component machining and automotive assembly, where high accuracy and large workspace movements are required. However, their forward kinematics can be highly coupled and be nonlinear. To reduce the time required to define the forward kinematics of a robot with parallel–serial structure, this paper introduces the use of neural networks. Two radial basis function networks are trained to learn the parallel and serial kinematics separately, and then integrated into a complete model. The error of this network model is analyzed and identified by a particle swarm optimization algorithm. Simulation and experiment results are obtained from the hybrid robot, Exechon, which shows that the developed kinematic model is able to produce accurate position and orientation estimates of the end-effector. The computation time of the neural network model is greatly reduced when compared to the time achieved by the numerical model. KEYWORDS: Hybrid robot; Forward kinematics; Neural network; Particle swarm optimization. Nomenclature a Best position of all the particles. Best position (the position giving the best bi fitness value) of one particle. B, M, T Origins of the base form, moving platform, and tool tip. Positive constants. c1 , c2 f Fitness function. fnp Network-based tool tip position function. fno Network-based tool orientation function. Fitness function with regard to α1 , β1 , γ1 . fpt fpz Fitness function with regard to α2 , β2 , γ2 . gp Forward kinematic function of the parallel platform. Forward kinematic function of the serial gs wrist. * Corresponding author. E-mails:
[email protected]
Gtf Gtf L1 , L2 , L3 N Nr pt pt pitm M
pr
Pnet Q4 , Q5 r1 , r2 Rc1 Rc2 B
RM Rtf
Rtf S Snet U Vi W x b , yb , z b x m , ym , z m x t , yt , z t Xi zt z itm z t
Kinematic transformation used to generate B RM (with error). Real kinematic transformations used to generate B RM (without error). Parallel limb lengths. Number of particles in the swarm. Sampling resolution of one joint. Position vector of the tool tip. Position vector of the tool tip, where Q4 = Q5 = 0. Measured tool tip position for PSO identification. Tool tip displacement with regard to Q4 and Q5 . Neural network used to approximate gp . Serial joint angles. Uniform random numbers between 0 and 1. Rotation matrix representing differences between Gtf and Gtf . Rotation matrix representing differences between Gtf Rtf , and Gtf Rtf . Rotation matrix from frame M to B. Kinematic transformation used to generate M z t (with error). Real kinematic transformations used to generate M z t (without error). Number of the measured samples for identification. Neural network used to approximate gs . Joint position vector, U = (L1 , L2 , L3 , Q4 , Q5 ). Velocity of particle. Inertia weight. x, y, z axes of frame B. x, y, z axes of frame M. x, y, z axes of frame T. Position of particle. Orientation vector of the tool. Measured tool orientation for PSO identification. Orientation vector of the tool, where Q4 = Q5 = 0.
848 M
zt
α1 , β1 , γ1 α2 , β2 , γ2
Learning forward kinematics behavior of hybrid robot by artificial neural networks Orientation vector of the tool expressed in frame T. Euler angles of Rc1 . Euler angles of Rc2 .
1. Introduction In previous decades parallel robots have attracted a lot of attention from researchers and industry. Compared with the more commonly used serial robots, parallel robots have potential advantages in accuracy, dynamics, and stiffness but suffer from limited workspace. By proper combination of parallel and serial mechanisms, hybrid robots can achieve an increase in this workspace while maintaining accuracy, dynamics, and stiffness. A typical hybrid robot structure is composed of a fully parallel platform, with serial wrists mounted on the platform. One successful example of such hybrid robots is Tricept, which has been wildly used in the manufacturing industry.1 Forward kinematics of hybrid robots is used to determine the end-effector pose (including position and orientation) with regard to given joint positions. Although the parallel platform involved in a hybrid robot usually has lower mobility, its forward kinematic equations are still highly nonlinear and may have multiple solutions.2–4 Thus, the forward kinematics of parallel mechanisms is a fundamental problem in solving the hybrid kinematics. The traditional methods for this problem can be classified as the algebraic elimination method,5–7 Gr¨obner basis method,8,9 continuation method,10,11 and interval analysis method.12 The algebraic elimination and Gr¨obner basis methods focus on changing the kinematic equations into a highdegree univariate polynomial and then finding its roots. The continuation and interval analysis methods are actually numerical processes that can search all solutions to a forward kinematic equation system. Mathematically these methods are very complicated and computationally these are timeconsuming. Therefore, they are not attractive to industry applications, especially where real-time control is required. In addition, the forward kinematics problem is not fully solved by giving a set of possible solutions. Therefore, how to determine a unique solution is still a challenge.13 Finally, to implement these methods in parallel robots, the identification of the geometrical parameters (i.e. the calibration process) is another complicated problem that requires some dedicated procedures and tools.14–16 The artificial neural network (ANN), usually called neural network (NN), is actually a computational model inspired by human brain. It consists of numerous interconnected neurons and can approximate a complex system whose internal details are unknown.17,18 Some researchers have tried to use neural networks to learn the kinematics of parallel mechanisms. Boudreau et al.19 proposed a holographic neural network (HNN) to model a planar 3-degree-offreedom (DOF) manipulator. Dehghani and Ahmadi20 used multilayer perceptron (MLP) to solve forward kinematics of the parallel robot HEXA. Yee and Lim21 used neural networks to recognize the input–output relationships of the Stewart platform. However, so far the developed network models cannot satisfy the high accuracy required for the
Fig. 1. (Colour online) Neural network with one neuron.
discussed robot tasks such as machining aircraft parts and automotive manufacturing.22 The particle swarm optimization (PSO) algorithm was first proposed by Kennedy and Eberhart23 and is inspired by the swarm behavior of birds or fish. Each individual in the swarm can change its velocity and position, yet the whole swarm will converge to a target. Similarly, the PSO algorithm employs a population (called swarm) of candidate solutions (called particles) that can fly through the search space to find the optimal solution.24,25 The PSO algorithm does not calculate function gradient and therefore it does not require the exact expression of an optimization problem. This feature is very suitable for engineering applications. Some researchers have used PSO or its variants to figure out the best parameters of neural network.26,27 However, the PSO algorithm does suffer from very large search spaces if there are too many neurons in the network. In our study, the PSO algorithm is not directly implemented to train a neural network, but to identify an error compensator. This paper proposes to use the neural network and the PSO method to solve forward kinematics for hybrid robots with parallel–serial structure. The aim of this method is high accuracy, high computational speed, and ease of use. This paper is organized as follows. In Section 2 the overview of neural network and the PSO algorithm is briefly presented. In Section 3 a typical hybrid robot, Exechon, is introduced. In Section 4 the forward kinematics of Exechon is decoupled and transformed for network training. In Section 5 two radial basis function (RBF) networks are trained to approximate the decoupled kinematics and then integrated into a complete model. In Section 6 the error of this networkbased model is analyzed and then compensated by the PSO algorithm. In Section 7 the simulation and experiment results are presented; and in Section 8 the conclusions are presented.
2. Overview of Neural Network and PSO Algorithm This section briefly introduces the theory of neural networks and the PSO algorithm, as these are the basic tools in our research. 2.1. Neural network By learning from given samples (input/output pairs measured from an existing system) the neural network can approximate a complex system whose internal details are unknown.17,18 A neural network may contain a large number of interconnected neurons where the sum of the weighted inputs and a bias is applied to a linear or nonlinear transfer function to generate the output (Fig. 1).
Learning forward kinematics behavior of hybrid robot by artificial neural networks
is the inertia weight, c1 and c2 are positive constants, r1 and r2 are uniform random numbers between 0 and 1, bi (t) is the best position (the position giving the best fitness value) of particle i until iteration t, and a(t) is the best position of all the particles until iteration t. According to Eq. (1), V i (t) consists of three parts, where the first part is the inertia that prevents velocity from abrupt changes. Here large values of W facilitate global search, while its small values facilitate local search. The second part is the “personal” part, which represents the velocity change due to one particle’s own experience. The third part is the “social” part, which represents the velocity change due to the group experience of all particles.24 Compared with conventional optimization methods, such as the Quasi-Newton algorithm, PSO does not use the gradient of fitness function f, therefore it can be used on the optimization problems that are partially irregular, noisy, and have time-varying parameters.
Fig. 2. Training process. w(1) j ,i
x1
wk(2),j R1
∑
y1
R2 ... ...
... ...
... ...
∑
xp
yq
RN Input
Hidden layer
Output layer
Fig. 3. (Colour online) Typical RBF network.
The training (or learning) process requires a large number of given samples (Fig. 2) where the training algorithm adjusts the network weights until the error between the network outputs and given outputs is acceptable. A well-trained network can predict the outputs with regard to new inputs that are not included in the given samples. Different types of neural networks are designed for different purposes, such as function approximation, pattern recognition, and control system.18 The RBF network is employed in our study because it is capable of universal approximation to an arbitrary accuracy.22 It consists of a hidden layer, where RBFs are used in each neuron and a linear output layer (Fig. 3). The orthogonal least squares (OLS) algorithm is usually used for training the RBF network.28 2.2. PSO algorithm The PSO algorithm employs a number of candidate solutions to find an optimal solution. To do this, let f : Rn → R be the fitness or cost function, which needs to be minimized. This function takes a candidate solution as argument and produces a real number as output, which indicates the fitness of the given candidate solution. The goal is to find a solution a so that f (a) ≤ f (X) for all X in the search space, which means a is the global minimum. Let N be the number of particles in the swarm. Each particle has a position X i ∈ Rn in the search space and velocity V i ∈ Rn (for i = 1 to N). Then the PSO algorithm is24,25 V i (t + 1) = W V i (t) + c1 r1 [bi (t) − X i (t)] + c2 r2 [a(t) − X i (t)], X i (t + 1) = X i (t) + V i (t + 1),
849
3. Exechon Robot Our study is illustrated using a recently developed hybrid robot named Exechon. The Exechon robot was designed by Neumann as an improvement of the well-known Tricept robot.1,29 As shown in Fig. 4(a) the moving platform is supported by three actuated and parallel limbs, where limb 1 and limb 3 are symmetric with respect to limb 2. Each limb is connected to the base by a universal joint and to the moving platform by a revolute joint. The serial wrist is mounted on the moving platform and composed of two actuated rotation joints. The end-effector can realize 5-DOF movement in the workspace with regard to joint positions L1 , L2 , L3 , Q4 , and Q5 (Fig. 4(b)). In order to define the forward kinematics of Exechon, three Cartesian coordinate systems B(x b , yb , z b ), M(x m , ym , z m ), and T (x t , yt , z t ) are attached to the base platform, moving platform, and end-effector (in our case the tool), respectively (Fig. 4(b)). B is the origin of the base platform, M the origin of the moving platform, and T is the tool tip origin. (x b , yb, z b ), (x m , ym , z m ), and (x t , yt , z t ) are then unit vectors of reference frame B, M, and T, respectively, where the x b − yb plane contains three universal joints and the x m − ym plane contains three revolute joints. These revolute joints make the moving platform overconstrained and therefore ym is always perpendicular to x b .29 Pateloup et al.30 and Bi et al.31 numerically solved the forward kinematics problem of Exechon using the Newton–Raphson algorithm. To identify geometrical parameters, Chanal et al.32 proposed a new approach based on machining dedicated parts. This approach has been validated using a parallel robot called Verne, but for Exechon the validation is still in progress. The neural network can handle the forward kinematics modelling and parameter identification simultaneously, and is therefore more efficient than the previous methods.
(1) (2)
where V i (t) is the current velocity of particle i at iteration t, X i (t) is the current position of particle i at iteration t, W
4. Kinematics Transformation and Decoupling The forward kinematics of a hybrid robot can be considered as a multi-input, multi-output (MIMO) function mapping
850
Learning forward kinematics behavior of hybrid robot by artificial neural networks This 5-input-6-output hybrid kinematic function can be approximated by the RBF network. As we know, the training process of a neural network is based on a large number of input/output pairs sampled from the robot. For a 5-input6-output network the total number of the samples will be Nr5 , where Nr is the sampling resolution of each joint. If the hybrid kinematics can be decoupled into a parallel part with three actuated joints and a serial part with two actuated joints, then the total number of the samples will be reduced to Nr3 + Nr2 , which is much smaller than Nr5 . For the purpose of decoupling, the hybrid kinematics of Exechon, an intermediate tool tip position pt and corresponding tool orientation z t , where rotation angles Q4 and Q5 are zero, are introduced to calculate the final tool position and orientation as pt = pt + B RM M pr ,
(3)
z t = B RM M z t ,
(4)
where pt is the position vector of the tool tip expressed in frame B, pt is the position vector of the tool tip where Q4 = Q5 = 0,B RM is the rotation matrix from frame M to B, M pr is the tool tip displacement with regard to Q4 and Q5 , and is expressed in frame M, z t is the orientation vector of the tool expressed in frame B (i.e., the z-axis of frame T), and M z t is the orientation vector of the tool expressed in frame T. In an ideal condition without any assembly error, the tool orientation z t , where Q4 = Q5 = 0, represents the z-axis of frame M, z m . The y-axis of frame M, ym , is always perpendicular to the x-axis of frame B, x b , due to the overconstrained structure of Exechon. Thus, x m and ym can be derived from z t using cross-product, and B RM is obtained by B
RM = [x m =
[(z t
ym
zm ]
× x b ) × z t
z t × x b
= Gtf (z t ),
z t ] (5)
where x b = [1 0 0]T is the x-axis of frame B, and Gtf is the kinematic transformation mapping z t to B RM . In addition, M z t can be derived from the serial joint positions Q4 and Q5 as follows: M
Fig. 4. (Colour online) Exechon robot.
joint positions to end-effector position and orientation within the workspace. In the case of Exechon the inputs are five actuated joint positions, L1 , L2 , L3 , Q4 , and Q5 . The outputs are the tool tip position vector, pt = BT [x y z]T , and tool orientation vector, z t = [i j k]T , therefore there are six outputs.
zt = M RT T z t ⎞⎛ ⎛ ⎞ 1 0 0 cos Q4 − sin Q4 0 = ⎝ sin Q4 cos Q4 0⎠ ⎝0 cos Q5 − sin Q5 ⎠ 0 0 1 0 sin Q5 cos Q5 ⎛ ⎞ 0 (6) × ⎝0⎠ = Rtf (Q4 , Q5 ), 1
where M RT is the rotation matrix from frame T to frame M, z t = [0 0 1]T is the orientation vector of the tool expressed in frame T. Substituting Eq. (5) into Eq. (3) yields T
pt = pt + Gtf (z t )M pr ,
(7)
Learning forward kinematics behavior of hybrid robot by artificial neural networks Fixed serial angles Parallel legs
{
{
851
0 0
L1
Exechon
L2 L3
Fig. 5. (Colour online) Kinematics decoupling.
Training algorithm
p ′tx p ′ty p ′tz z ′tx z ′ty z ′tz
} }
pt′
zt′
Compare
and substituting Eqs. (5) and (6) into Eq. (4) yields zt = Gtf (zt )Rtf (Q4 , Q5 ),
(8)
where pt , z t , and M pr can be measured from the real robot. pt and z t depend on the parallel limb lengths L1 , L2 , and L3 , while M pr depends on the serial joint angles Q4 and Q5 .
Pnet Fig. 6. (Colour online) Parallel kinematics learning.
Thus, they can be considered as
pt z t M
= gp (L1 , L2 , L3 ), pr = gs (Q4 , Q5 ),
(9) (10)
where gp is the forward kinematic function of the parallel platform, and gs is the forward kinematic function of the serial wrist. Substituting Eqs. (9) and (10) into Eq. (7) yields pt = gp (L1 , L2 , L3 ) + Gtf (gp (L1 , L2 , L3 ))gs (Q4 , Q5 ), (11) and substituting Eq. (9) into Eq. (8) yields z t = Gtf (gp (L1 , L2 , L3 ))Rtf (Q4 , Q5 ).
(12)
Thus, the hybrid kinematics of Exechon is decoupled into parallel and serial kinematics by gp and gs , respectively (Fig. 5).
5. Forward Kinematics Learning In this section two neural networks are trained to learn the decoupled kinematic functions gp and gs . Pnet is the neural network used to approximate gp , and Snet is the neural network used to approximate gs . The training processes are based on the inputs and outputs measured from the real robot. 5.1. Parallel kinematics learning As with the kinematics function gp , network Pnet has three inputs, L1 , L2 , and L3 , and six outputs contained in vectors pt and z t . In order to learn the parallel kinematics function, gp , both serial joint positions Q4 and Q5 are fixed to zero and pt and z t are measured with regard to different configurations of L1 , L2 , and L3 (Fig. 6).
Because of the overconstrained structure of Exechon, ym is always perpendicular to x b . Thus, the outputs of Pnet containing one orientation vector z t is able to define B RM according to Eq. (5). However, in the case of other hybrid robots, ym is not guaranteed to be perpendicular to x b and therefore Eq. (5) does not exist. To define B RM in this case two orthogonal axes of frame M need to be measured and included in the outputs of Pnet . Thus, Pnet will become a 3-input-9-output network. 5.2. Serial kinematics learning As with the kinematic function, gs , network Snet has two inputs, Q4 and Q5 , and three outputs in vector M pr . To learn the serial kinematics function, gs , the parallel limb lengths L1 , L2 , and L3 are fixed. Thus, the pose of the moving platform and the corresponding rotation matrix, B RM , is fixed. The tool tip displacements with regard to different configurations of Q4 and Q5 are measured in frame B and transformed to frame M by multiplying the inverse of B RM (Fig. 7). In our study, the parallel limb lengths were chosen as L1 = 980 mm, L2 = 1060 mm, and L3 = 980 mm. The choice of limb lengths is not unique but should be between the stroke limitation of 900 mm and 1600 mm. 5.3. Network-based kinematic model After training, Pnet and Snet are capable of approximating the parallel and serial kinematic functions gp and gs . Replacing gp and gs in Eqs. (11) and (12) by Pnet and Snet yields pt = Pnet (L1 , L2 , L3 ) + Gtf (Pnet (L1 , L2 , L3 ))Snet (Q4 , Q5 ) = pt + Gtf (z t )M pr ,
(13)
z t = Gtf (Pnet (L1 , L2 , L3 ))Rtf (Q4 , Q5 ) = Gtf (z t )Rtf (Q4 , Q5 ).
(14)
Figure 8 illustrates this network-based kinematic model.
852
Learning forward kinematics behavior of hybrid robot by artificial neural networks Fixed parallel legs
Serial angles
{
{
980
ptx
1060
pry
Exechon
980
prz
Q4 Q5
}
pr inv( B RM ) M
Training algorithm
In Eqs. (13) and (14) Gtf and Rtf are used to provide rotation transformations, thus their errors can be compensated by multiplying additional rotation matrices as follows:
pr
Fig. 7. (Colour online) Serial kinematics learning.
L2
pt′ Pnet
zt′
B
RM
pt
G tf
L3
M
Q4
pr
Snet Q5 M
zt
(15)
Gtf Rtf = Rc2 Gtf Rtf ,
(16)
where Gtf and Rtf are the real kinematic transformations in the robot, Rc1 is the rotation matrix representing the differences between Gtf and Gtf , and Rc2 is the rotation matrix representing the differences between Gtf Rtf and Gtf Rtf . Rc1 and Rc2 can be defined by the generic Euler rotation as follows:
Compare
Snet
L1
Gtf = Rc1 Gtf ,
zt
R tf
Fig. 8. (Colour online) Network-based kinematic model.
6. Error Compensation In Eqs. (13) and (14) the two RBF networks, Pnet and Snet are used to approximate the parallel and serial kinematic functions, gp and gs . Their outputs pt , z t , and M pr are then transformed to the tool tip position pt and tool orientation z t by the kinematic transformations, Gtf and Rtf . Thus, the final accuracy depends on the accuracy of Pnet and Snet , Gtf and Rtf . Experiment results show that the network outputs, pt , z t , and M pr , can achieve a relatively high accuracy of around 6 μm individually. However, the final accuracy achieved by combining them is decreased to 30 μm. This means that there are kinematic transformation errors in Gtf and Rtf .
Rc1 (α1 , β1 , γ1 ) ⎞⎛ ⎞ ⎛ cosβ1 0 sinβ1 1 0 0 1 0 ⎠ = ⎝0 cosα1 −sinα1 ⎠ ⎝ 0 0 sinα1 cosα1 −sinβ1 0 cosβ1 ⎛ ⎞ cosγ1 −sinγ1 0 × ⎝ sinγ1 cosγ1 0⎠, (17) 0 0 1
Rc2 (α2 , β2 , γ2 ) ⎛ ⎞⎛ ⎞ 1 0 0 cosβ2 0 sinβ2 1 0 ⎠ = ⎝0 cosα2 −sinα2 ⎠ ⎝ 0 −sinβ2 0 cosβ2 0 sinα2 cosα2 ⎞ ⎛ cosγ2 −sinγ2 0 × ⎝ sinγ2 cosγ2 0⎠. (18) 0 0 1 If (α1 , β1 , γ1 ) and (α2 , β2 , γ2 ) can be identified, the transformation errors of Gtf and Rtf can then be compensated for by using Eq. (15) through (18) in Eqs. (13) and (14). 6.2. PSO-based error identification Two rotation matrices, Rc1 and Rc2 , are introduced to Eqs. (13) and (14) to compensate for the transformation errors in Gtf and Rtf : pt = Pnet (L1 , L2 , L3 ) + Rc1 (α1 , β1 , γ1 )Gtf × (Pnet (L1 , L2 , L3 ))Snet (Q4 , Q5 ),
(19)
z t = Rc2 (α2 , β2 , γ2 )Gtf (Pnet (L1 , L2 , L3 ))Rtf (Q4 , Q5 ). 6.1. Transformation error compensation The kinematic transformations, Gtf and Rtf , are defined by Eqs. (5) and (6), respectively. Equation (5) is formulated by assuming that y-axis of frame M, ym , is strictly perpendicular to the x-axis of frame B, x b . Equation (6) is formulated by assuming that the rotation angles of the serial wrist exactly follow the inputs Q4 and Q5 . In fact, these assumptions cannot be completely guaranteed because the real robot may have assembly and tracking errors. Thus, Gtf and Rtf as defined by Eqs. (5) and (6), respectively, may be different from the real kinematic transformations in the robot.
(20) (α1 , β1 , γ1 ) and (α2 , β2 , γ2 ) can be identified by minimizing the distance between the measured tool pose from the real robot and the calculated tool pose from the networks according to Eqs. (19) and (20). Thus, Eqs. (19) and (20) can be rewritten as pt = fnp (U, α1 , β1 , γ1 ),
(21)
z t = fno (U, α2 , β2 , γ2 ),
(22)
Learning forward kinematics behavior of hybrid robot by artificial neural networks
853
Table I. Joint range for experiment. Joint position
Min.
Max.
L1 (mm) L2 (mm) L3 (mm) Q4 (degree) Q5 (degree)
975 1055 975 −15 35
995 1075 995 15 55
where U = [L1 , L2 , L3 , Q4 , Q5 ], fnp is the network-based tool tip position function, and fno is the network-based tool orientation function. The distance between the measured tool tip position and calculated tool tip position can be defined as
S
i
fpt (α1 , β1 , γ1 ) = ptm − fnp (U i , α1 , β1 , γ1 ) S, i=1
Fig. 9. (Colour online) Accuracy of the network-based kinematic model.
(23) where S is the number of the measured samples for identification, pitm is the measured tool tip position, and fnp (U i , α1 , β1 , γ1 ) is the calculated tool tip position, where i = 1, 2, . . . S. Similarly, the distance between the measured tool orientation and calculated tool orientation can be defined as S
z i − fno (U i , α2 , β2 , γ2 )
S, fzt (α2 , β2 , γ2 ) = tm i=1
(24) where z itm is the measured tool orientation, and fno (U i , α2 , β2 , γ2 ) is the calculated tool orientation. fpt and fzt are actually the fitness functions of (α1 , β1 , γ1 ) and (α2 , β2 , γ2 ), respectively. Conventional optimization algorithms typically search for the minimum of a function by calculating the function gradient. In Eqs. (23) and (24), fnp and fno are concerned with neural networks whose exact expressions are unknown. Thus, conventional optimization algorithms cannot deal with this problem and the PSO algorithm is employed. A number of candidate (α1 , β1 , γ1 ) and (α2 , β2 , γ2 ) particles are initialized randomly and updated iteratively according to Eqs. (1) and (2), where the iteration process will stop once fpt (α1 , β1 , γ1 ) and fzt (α2 , β2 , γ2 ) are minimized. Applying the resulting (α1 , β1 , γ1 ) and (α2 , β2 , γ2 ) to Eqs. (19) and (20), can efficiently compensate for the transformation errors in Gtf and Rtf .
7. Simulation and Experiment All the methods proposed in Sections 5 and 6 were validated by simulation and experiment with regard to the joint space given by Table I. The corresponding workspace in frame B is within a volume of 150 × 100 × 150mm. This section first
presents a network-training scheme, and then applies it to the simulation and experiment. 7.1. Training scheme The training process includes the following three steps: (1) Sixty samples whose inputs are uniformly distributed in the parallel joint space are collected. Forty of these samples were used to train the Pnet , while the remaining were used to evaluate accuracy. In this step, the limb lengths L1 , L2 , and L3 were changed within the range according to Table I, and the angles of the serial joints Q4 and Q5 were set to zero. (2) Forty-seven samples whose inputs are uniformly distributed in the serial joint space are collected. Thirtyfive of these samples were used to train the Snet , while the remaining were used to evaluate accuracy. As mentioned in Section 5, the choice of limb lengths is not unique. In this step they were fixed to L1 = 980 mm, L2 = 1060 mm, and L3 = 980 mm, and the serial angles Q4 and Q5 varied within the range as given in Table I. (3) Twenty samples whose inputs are randomly distributed within the entire joint space are collected to evaluate the total accuracy of the combined Pnet and Snet according to Eqs. (13) and (14). 7.2. Simulation In simulation Pnet and Snet were trained using a numerical model developed by Pateloup et al.30 The accuracy of the neural network model is evaluated by comparing its outputs with the outputs of the numerical model. Figure 9 illustrates the training results. It was found that the neural network model achieves total accuracy of less than 0.3 μm and 3.5 × 10−7 rad within the given training volume. Table II compares the computational time of neural network model with that of the numerical model. After training, the neural networks can generate the output by algebraic calculation without any iterative computation and is therefore much faster than the numerical model. The tests
854
Learning forward kinematics behavior of hybrid robot by artificial neural networks Table IV(a). Position accuracy of neural network with compensation.
Average error (μm) Maximum error (μm)
Pnet
Snet
Total
5.13 12.86
6.90 16.21
8.86 15.09
Table IV(b). Orientation accuracy of neural network with compensation.
Average error (rad) Maximum error (rad)
Fig. 10. (Colour online) The Leica laser tracker. Table II. Computation time comparison. Number of random points
Computation time (s) of numerical model
Computation time (s) of network model
50 100 300 500 1000
3.25 6.92 19.91 31.85 66.99
0.37 0.76 2.20 3.35 6.84
Table III(a). Position accuracy of neural network without compensation.
Average error (μm) Maximum error (μm)
Pnet
Snet
Total
5.13 12.86
6.90 16.21
24.26 35.46
Table III(b). Orientation accuracy of neural network without compensation.
Average error (rad) Maximum error (rad)
Pnet
Snet
Total
8.34 × 10−5 1.90 × 10−4
Null Null
1.8 × 10−4 3.6 × 10−4
were performed in the Matlab environment by a 1.8-GHz computer with 1-GB RAM. 7.3. Experiment In experiment Pnet and Snet were trained using the real Exechon robot. A Leica laser tracker was employed to measure the tool tip position and obtain tool orientation (Fig. 10). The absolute accuracy of this laser tracker was 5 μm. Table III shows the training results without error compensation. It can be seen that although the accuracy of Pnet and Snet individually are satisfactory, the total accuracy is much worse. This is mainly due to the errors in the kinematic
Pnet
Snet
Total
8.34 × 10−5 1.90 × 10−4
Null Null
1.03 × 10−4 2.01 × 10−4
transformations Gtf and Rtf found in Eqs. (13) and (14) respectively. In order to compensate for the kinematic transformation errors in Gtf and Rtf , two rotation matrices, Rc1 and Rc2 , are introduced to Eqs. (13) and (14), and then identified using the PSO algorithm. Another 10 samples were measured to evaluate the fitness of each particle according to Eqs. (23) and (24). Table IV gives the training results with error compensation. It can be seen that the total accuracy is now close to the accuracy of Pnet and Snet , meaning that the transformation errors in Gtf and Rtf have been reduced.
8. Conclusions In this paper the neural network method combined with PSO is proposed and implemented to solve the forward kinematics of a hybrid robot aiming for high accuracy, low computational time, and ease of use. In order to reduce the number of training samples, the hybrid kinematics was decoupled into parallel and serial kinematics and then approximated by two RBF networks. Individually, each network can achieve a high accuracy of 6 μm. However, the combined accuracy without error compensation was 25 μm. Therefore, a PSO algorithm was used to identify and compensate for the transformation errors, and improved total accuracy to 9 μm. The neural network also has a distinct advantage in computational speed, which is important for real-time applications. We found the computation time of the neural network model to be approximately 89% faster than that of the numerical model developed by Pateloup et al.30 The proposed NN–PSO method is a general solution to the forward kinematics problem of hybrid robots with parallel– serial structure.
Acknowledgments This work was carried out within the framework of the TIMS Research Group, using grants from the Regional Council of Auvergne, the French Ministry of Research, the CNRS, and the Cemagref.
Learning forward kinematics behavior of hybrid robot by artificial neural networks References 1. K. E. Neumann, “Robot,” US Patent 4732525 (United States Patent Office, Alexandria, VA, 1988). 2. G. Gogu, “Mobility Criterion and Overconstraints of Parallel Manipulators,” Proceedings of International Workshop on Computational Kinematics, Cassino, Italy (2005). 3. J. S. Dai, Z. Huang and H. Lipkin, “Mobility of overconstrained parallel mechanisms,” ASME J. Mech. Des. 128(1), 220–229 (2006). 4. J. P. Merlet, Parallel Robots (Springer, Dordrecht, Netherlands, 2006) 5. M. L. Husty, “An algorithm for solving the direct kinematic of Stewart–Gough-type platforms,” Mech. Mach. Theory 31(4), 365–380 (1996). 6. T. Y. Lee and J. K. Shim, “Forward kinematics for the general 6–6 Stewart platform using algebraic elimination,” Mech. Mach. Theory 36(9), 1073–1085 (2001). 7. X. G. Huang, Q. Z. Liao, S. M. Wei, X. Qiang and S. G. Huang, “Forward Kinematics of the 6–6 Stewart Platform with Planar Base and Platform Using Algebraic Elimination,” Proceedings of the IEEE International Conference on Automation and Logistics, Jinan, China (2007). 8. D. Lazard, “Stewart Platform and Gr¨obner Basis,” Proceedings of ARK, Ferrare, Italy (1992). 9. X. G. Huang and G. P. He, “Forward Kinematics of the General Stewart–Gough Platform Using Gr¨obner Basis,” Proceedings of the 2009 IEEE International Conference on Mechatronics and Automation, Changchun, China (2009). 10. M. Raghavan, “The Stewart platform of general geometry has 40 configurations,” J. Mech. Des. 115, 277–282 (1993). 11. A. J. Sommese, J. Verschelde and C. W. Wampler, “Advances in polynomial continuation for solving problems in kinematics,” Trans. ASME 126, 262–268 (2004). 12. J. P. Merlet, “Solving the forward kinematics of a Gough-type parallel manipulator with interval analysis,” Int. J. Robot. Res. 23(3), 221–235 (2004). 13. J. P. Merlet, “Closed-Form Resolution of the Direct Kinematics of Parallel Manipulators Using Extra Sensors Data,” Proceedings of 1993 IEEE International Conference on Robotics and Automation, Atlanta, USA (1993). 14. W. Khalil, G. Garcia and J. F. Delagarde, “Calibration of the Geometric Parameters of Robots Without External Sensors,” Proceedings of the 1995 IEEE International Conference on Robotics and Automation, Nagoya, Japan (1995). 15. H. Zhuang, “Self-calibration of parallel mechanisms with a case study on Stewart platforms,” IEEE Trans. Robot. Autom. 13(3), 387–397 (1997). 16. S. Besnard and W. Khalil, “Identifiable Parameters for Parallel Robots Kinematic Calibration,” Proceedings of the 2001 IEEE International Conference on Robotics and Automation, Seoul, Korea (2001). 17. G. L. Luo and S. Y. Qin, An Introduction to Intelligent Controls (Zhejiang Science and Technology, Hangzhou, China, 1997).
855
18. M. T. Hagan, H. B. Demuth and M. H. Beale, Neural Network Design (PWS, Boston, MA, USA 1996). 19. R. Boudreau, G. Levesque and S. Darenfed, “Parallel manipulator kinematics learning using holographic neural network models,” Robot. Comput.-Integr. Manuf. 14, 37–44 (1998). 20. M. Dehghani, M. Ahmadi, A. Khayatian, M. Eghtesad and M. Farid, “Neural Network Solution for Forward Kinematics Problem of HEXA Parallel Robot,” Proceedings of 2008 American Control Conference (ACC), Seattle, WA, USA (2008). 21. C. S. Yee and K. Lim, “Forward kinematics solution of Stewart platform using neural networks,” Neurocomputing 16, 333–349 (1997). 22. N. Hennes, “An Innovative Machinery Concept for High Performance 5-Axis Machining of Large Structural Components in Aircraft Engineering,” Proceedings of 3rd Chemnitz Parallel Kinematic Seminar, Chemnitz, Germany (2002). 23. J. Kennedy and R. Eberhart, “Particle Swarm Optimization,” Proceedings of IEEE International Conference on Neural Networks (ICNN), Perth, Australia (1995). 24. Y. Shi and R. Eberhart, “Parameter Selection in Particle Swarm Optimization,” Proceedings of the 1998 Conference on Evolutionary Computation, Alaska, USA (1998). 25. R. Eberhart and Y. Shi, “Particle Swarm Optimization: Developments, Applications and Resources,” Proceedings of Congress on Evolutionary Computation 2001, Seoul, Korea (2001). 26. J. L. Zhou, Z. C. Duan, Y. Li, J. C. Deng and D. Y. Yu, “PSObased neural network optimization and its utilization in a boring machine,” J. Mater. Process. Technol. 178, 19–23 (2006). 27. J. B. Yu, S. J. Wang and L. F. Xia, “Evolving artificial neural networks using an improved PSO and DPSO,” Neurocomputing 71, 1054–1060 (2008). 28. S. Chen, C. F. N. Cowan and P. M. Grant, “Orthogonal least squares learning algorithm for radial basis function networks,” IEEE Trans. Neural Netw. 2(2), 302–309 (1991). 29. K. E. Neumann, “Exechon Concept – Parallel Kinematic Machines in Research and Practice,” Proceedings of 5th Chemnitz Parallel Kinematics Seminar, Chemnitz, Germany (2006). 30. S. Pateloup, H. Chanal and E. Duc, “Geometric and Kinematic Modelling of a New Parallel Kinematic Machine Tool: The Tripteor X7 Designed by PCI,” Proceedings of 7th International Conference of Numerical Analysis and Applied Mathematics, Tarbes, France (2009). 31. Z. M. Bi, Y. Jin, R. Gibson and P. McTotal, “Kinematics of Parallel Kinematic Machine Exechon,” Proceedings of the 2009 IEEE International Conference on Information and Automation, Zhuhai/Macau, China (2009). 32. H. Chanal, E. Duc, P. Ray and J. Y. Hasco¨et, “A new approach for the geometrical calibration of parallel kinematics machines tools based on the machining of a dedicated part,” Int. J. Mach. Tools Manuf. 47, 1151–1163 (2007).