In order to improve the low output accuracy caused by the elastic deformations of the branch chains, a finite element-based dynamic accuracy analysis method for parallel mechanisms is proposed in this paper. First, taking a 5-prismatic-spherical-spherical (PSS)/universal-prismatic-universal (UPU) parallel mechanism as an example, the error model is established by a closed vector chain method, while its influence on the dynamic accuracy of the parallel mechanism is analyzed through numerical simulation. According to the structural and error characteristics of the parallel mechanism, a vector calibration algorithm is proposed to reduce the position and pose errors along the whole motion trajectory. Then, considering the elastic deformation of the rod, the rigid-flexible coupling dynamic equations of each component are established by combining the finite element method with the Lagrange method. The elastodynamic model of the whole machine is obtained based on the constraint condition of each moving part, and the correctness of the model is verified by simulation. Moreover, the effect of component flexibility on the dimensionless root mean square error of the displacement, velocity and acceleration of the moving platform is investigated by using a Newmark method, and the mapping relationship of these dimensionless root mean square errors to dynamic accuracy is further studied. The research work provides a theoretical basis for the design of the parameter size of the prototype.
1 Introduction
Compared with the serial mechanism, the parallel mechanism has advantages of greater stiffness, higher precision, reduced inertia, and higher payload to weight ratio [1‐4]. It has been widely used in aerospace, food processing, vehicle and ship industry, and medical equipment fields [5‐8].
The geometric errors of mechanical parts are inevitably produced in the process of processing and assembly. The error calibration method can effectively reduce the influence of geometric errors on the accuracy of the parallel mechanism [9, 10]. The calibration method is very important for geometric error compensation. The common calibration methods include external calibration, constraint calibration and self-calibration. The pose of the parallel mechanism is directly measured through external precision equipment in the external calibration method [11‐13], which can identify the geometric parameters of the moving platform. However, it has several disadvantages such as low calibration efficiency, high cost, and poor external anti-interference ability, etc. In the constraint calibration method [14‐16], the kinematic calibration is performed by imposing constraints on the system to limit the local motion capability of the mechanism components. Compared with the external calibration method, the constraint calibration method is relatively simple to operate and does not require expensive external measuring equipment, but it restricts the mechanical part motion characteristics, which makes it difficult to identify all kinematic parameters. The self-calibration method [11, 14, 17] only needs the extra redundant information of internal sensors of the mechanism to form full closed-loop control. In view of the economy of hardware and simplification of control system, the self-calibration method is adopted in our study. Meanwhile, the error calibration can improve the motion accuracy of the mechanism, which is of great significance to the dynamic accuracy analysis of the parallel mechanism [18, 19].
Advertisement
Dynamic accuracy is an important performance index for a parallel mechanism [20‐22], which requires that the actual motion state of the mechanism is as consistent as possible with the desired motion state. Accordingly, it is necessary to study the influence law of error factors on the dynamic accuracy of the parallel mechanism in the design stage of the mechanism. The performance of the system is often significantly reduced, while the failure rate will increase or even cause major losses if these error factors are not fully taken into account. Therefore, the dynamic accuracy of a precision mechanism is worthy of in-depth study. Yun et al. [23] established a kinematics model of an 8-PSS/SPS parallel mechanism system via the stiffness model and Newton-Raphson method, where Kane’s method was used to build up the dynamics model for analyzing the workspace, motion precision and dynamic characteristics. The size ranges of leg of a 3-DOF UPU parallel mechanism were obtained from sensitivity analysis in Ref. [24]. Based on the design and sensitivity analysis, the parallel mechanism was developed and various experiments have shown that the manipulator exhibited high accuracy and precision. In Ref. [25], the elastic dynamic equations of a flat-shaped parallel robot were derived, and the effects of two commonly used static balancing techniques on the dynamic performance of closed-chain mechanisms were deeply analyzed. The finite element method [26] was used to derive the elastodynamic equation of a plane high-precision linkage, and its dynamic characteristics and also natural frequency were analyzed. Taking the plane 3-PRR parallel mechanism as the object [27], a mechanism dynamics model with the clearance of the rotating pair was established. The root mean squared error (RMSE) was proposed as the index to quantify the effect of joint clearance on the dynamics of the system. As discussed above, the rigid body models were usually adopted as the research object, while the finite element method was used for analyzing the dynamic accuracy of the planar parallel mechanism. Few related studies on dynamic accuracy, caused by the elastic deformation of the spatial parallel mechanism, were analyzed due to the complexity of elastic dynamic model.
The elastic deformation of the branch chain of the mechanism will cause elastic vibration, which leads to the pose error of the moving platform [28, 29]. Therefore, the study of flexible deformation is very important to improve the dynamic accuracy of the mechanism. Taking a 5PSS/UPU coupling mechanism as an example [30, 31], a closed vector chain method is proposed to reduce the influence of geometric errors on dynamic accuracy. Combing the finite element method with Lagrange method, the rigid-flexible coupling elastic dynamic equation of the system was established, and the effect of dynamic accuracy of component flexibility on the parallel mechanism was further analyzed. Finally, the design principle for the mechanism parameter of the prototype was obtained.
This paper is organized as follows. In Section 2, the influence of geometric error on the dynamic accuracy of the 5-PSS/UPU parallel mechanism is studied, and the calibration method of geometric errors for the parallel mechanism is proposed. Section 3 establishes the rigid-flexible coupled model and analyzes the influence of the flexibility of the links on the dynamic accuracy of the parallel mechanism. Subsequently, numerical simulations are carried out. The conclusions are outlined in Section 4.
2 Analysis of Geometric Error
2.1 Error Modeling of 5-PSS/UPS Parallel Mechanism
The basic structure of the 5-PSS/UPU parallel mechanism is shown in Figure 1. It consists of a fixed base, a mobile platform and six branches connecting the two. The six branches include five PSS joint branches and one UPU joint branch. The symmetrically distributed PSS branched chains are the power input of the parallel mechanism, while the UPU branched chain provides constraints on the mechanism. Each drive branch is composed of 1 prismatic pair and 2 spherical pairs. The structure diagram of the 5-PSS/UPU parallel mechanism is shown in Figure 2, which depicts the fixed coordinate system O-XYZ and moving coordinate system D-XDYDZD. D and O are the centers of the moving and fixed platforms respectively. The Z axis is perpendicular to the static platform, the X axis is from the coordinate origin to point A1, and the Y axis is determined by the right-hand rule. The ZD axis is perpendicular to the moving platform upwards, the XD axis is from the coordinate origin to point C1, and the YD axis is determined by the right-hand rule. Ei-XEiYEiZEi is the local coordinate system where the origin coincides with Ai, the YEi axis coincides with AiBi, the XEi axis is perpendicular to OEi, and the ZEi-axis is determined by the right-hand rule, where i = 1, 2, 3, 4, 5, 6.
×
×
Advertisement
In the fixed coordinate system O-XYZ, the error model of the 5-PSS/UPU mechanism is established by vector method. The vector closed loop equation of a branch of the parallel mechanism can be expressed as
where D is the position vector of the coordinate origin of the dynamic coordinate system; \({}_{D}^{O} {\varvec{R}}\) is the rotation matrix from the dynamic coordinate system to the fixed coordinate system; si denotes the direction vector of the i-th driving branch; ni represents the direction vector of the link of the i-th branch. Li and li denote the length of the i-th flexible link and displacement of the i-th actuator, respectively.
Assuming that all error sources are small variables, differentiating Eq. (1) can be rewritten as
\({\varvec{\varepsilon}}_{D} = \left[ {{\text{d}}\gamma_{D} ,{\text{d}}\beta_{D} ,{\text{d}}\alpha_{D} } \right]^{{\text{T}}}\) represents the differentiation of the rotation angle of the moving platform around the X, Y and Z axes.
Eq. (2) can be rewritten by taking the dot products of both sides with vector \({\varvec{n}}_{i}^{{\text{T}}}\) as
The error can be approximated as a kind of differentiation since it is a small variable. The error mapping model of the parallel mechanism can be expressed as
where \(\delta {\varvec{W}}\) denotes the position and pose error of the moving platform. \(\delta{\varvec{\varLambda}}\) represents the input error of driving displacement. \(\delta {\varvec{L}}\) is the length error of a fixed link. \(\delta {}^{D}{\varvec{C}}\) is the position error of the spherical hinge at the moving platform. \(\delta {\varvec{A}}\) is the error of the apical position of the linear actuator. \(\delta {\varvec{S}}\) is the direction error of the linear actuator. \({\varvec{J}}_{W}\) is the Jacobian matrix of error transmission. \({\varvec{G}}_{L}\) is the coefficient matrix of link length error. \({\varvec{G}}_{C}\) is the coefficient matrix of the position error of spherical hinge at the moving platform. \({\varvec{G}}_{A}\) is the coefficient matrix of apical position error of linear actuator. \({\varvec{G}}_{S}\) is the error coefficient matrix of the linear actuator direction.
The Jacobian matrix of error transmission is invertible if the parallel mechanism is in a nonsingular configuration. Eq. (4) can be abbreviated as
\({\text{with}}\;\left\{ \begin{aligned} {\varvec{K}} &= {\varvec{J}}_{W}^{ - 1} [{\varvec{E}}_{5} \, {\varvec{G}}_{L} \, {\varvec{G}}_{C} \, {\varvec{G}}_{A} \, {\varvec{G}}_{5} ] \hfill \\ \delta p & = [\delta{\varvec{\varLambda}}^{{\text{T}}} \, \delta {\varvec{L}}^{{\text{T}}} \, \delta {\varvec{C}}^{{\text{T}}} \, \delta {\varvec{A}}^{{\text{T}}} \, \delta {\varvec{S}}^{{\text{T}}} ] \hfill \\ \end{aligned} \right.,\)where \({\varvec{K}}\) represents the mapping matrix of geometric error. \(\delta {\varvec{p}}\) denotes the geometric error source of the parallel mechanism. In \(\delta {}^{D}{\varvec{C}},\)\(\delta {\varvec{A}}\) and \(\delta {\varvec{S}},\) there are errors in the x, y and z axis directions.
\(\delta {\varvec{p}}\) of Eq. (5) includes 11 error sources of the parallel mechanism. Among them, the z-direction error of linear actuator apex \(\delta A_{z}\) is 0. Since the direction vector of linear actuator along the x, y and z axes of the three errors are not independent of each other, two independent error parameters (declinations \(\delta \varphi\) and \(\delta \theta\)) are used to facilitate the analysis of error sensitivity, as shown in Figure 3.
×
In Figure 3, \(\delta \varphi = \varphi^{\prime} - \varphi ,\)\(\delta \theta = \theta^{\prime} - \theta .\) The relationship between \(\delta \varphi ,\)\(\delta \theta\) and \(\delta s_{x} ,\)\(\delta s_{y} ,\)\(\delta s_{z}\) can be expressed as
where both \(\varphi\) and \(\theta\) are known quantity. The expressions of \(\delta \varphi\) and \(\delta \theta\) can be derived from Eq. (6), so 11 error sources can be reduced to 9 independent error sources.
2.2 Calibration of Geometric Errors
According to the structural characteristics and driving mode of the 5-PSS/UPU parallel mechanism, a vector calibration algorithm based on the inverse position solution is used to calibrate the geometric error. The positioning accuracy of actuator can be ignored since the high-precision screw module has high repetitive position accuracy.
When considering the existence of errors, Eq. (1) can be written as
where \({\varvec{D}},\)\({}_{D}^{O} {\varvec{R}}\) and \({\varvec{n}}_{i}\) in Eqs. (1) and (7) are identical in the same pose of the moving platform. By subtracting the two equations, the new equation is taken the dot products of both sides with vector \({\varvec{n}}_{i}^{{\text{T}}}\) as
Error sources \(\delta {}^{D}{\varvec{C}}_{i}\) and \(\delta {\varvec{s}}_{i}\) contain two independent error parameters. There are eight unknown error parameters in Eq. (8), and the five branches include 40 unknown error parameters. Five equations can be obtained by measuring posture of the moving platform, thereby at least 8 groups of different mechanism position parameters, which are required to be different as large as possible between them to reduce the coupling effect of each error parameter. According to actual condition, several sets of position parameters are measured and took the average of that to obtain higher calibration accuracy.
The vector calibration algorithm is used to identify the parameters of the 5-PSS/UPU parallel mechanism. Adopting Eq. (5) and the error data of Figure 4 as the actual size error, different position parameters can be obtained in terms of the actual structure size of the parallel mechanism, which is used to replace the actual measured position parameters. The actual structure size parameters and mechanism size parameters obtained by identification are regarded as the input and output of the calculation of vector calibration. Finally, the input and output parameters are compared to evaluate the accuracy of the calibration algorithm. The actuator branched chain 1 is selected for simulation calculation, and the pose parameters given by the actual structure size of the parallel mechanism (Table 1).
Table 1
Posture parameter samples
Sample number
γ (rad)
β(rad)
n1x (mm)
n1y (mm)
n1z (mm)
l1 (mm)
1
0.0217
0.0217
− 0.5622
0.0093
0.8270
8.6538
2
0.0468
0.0468
− 0.5354
0.0196
0.8444
19.6880
3
0.0672
0.0672
− 0.5127
0.0280
0.8581
29.3322
4
0.0811
0.0811
− 0.4970
0.0337
0.8671
36.2070
5
0.0871
0.0871
− 0.4902
0.0362
0.8709
39.2365
6
0.0845
0.0845
− 0.4931
0.0351
0.8692
37.9234
7
0.0737
0.0737
− 0.5055
0.0307
0.8623
32.4848
8
0.0556
0.0556
− 0.5257
0.0233
0.8504
23.7929
×
As shown in Table 2, the error values were obtained by the vector calibration algorithm according to Eq. (8). One can find that most of the calibration values obtained by the vector calibration method have an accuracy of more than 90%, which indicates the correctness and effectiveness of the calibration method. The reason for affecting the accuracy is that the driving input error is ignored. In addition, it is noteworthy that sensors also have some accuracy problems in real situation, so the accuracy of the actual calibration results will be lower than that of the simulation results. On the whole, the vector calibration method is generally effective for the calibration of 5-PSS/UPU parallel mechanism.
Table 2
Calibration results
Error source
Real value
Calibration value
Accuracy rate (%)
\(\delta L_{1}\)
0.255
0.239
93.42
\(\delta^{D} C_{1x}\)
− 0.144
− 0.130
90.06
\(\delta^{D} C_{1y}\)
0.00542
0.00601
88.89
\(\delta^{D} C_{1z}\)
0.0143
0.0155
91.61
\(\delta A_{1x}\)
− 0.103
− 0.110
92.50
\(\delta A_{1y}\)
− 0.234
− 0.221
94.65
\(\delta \theta_{1}\)
0.237
0.247
95.44
\(\delta \varphi_{1}\)
0.116
0.108
93.37
To further verify the effectiveness of calibration for improving dynamic accuracy, the position and pose errors of the moving platform before and after the calibration were compared. The specific process is that the joint displacement is obtained by using the inverse kinematics solution in a given the trajectory of the moving platform, and then the motion trajectory error before and after calibration is compared after substituting it into the actual model. The error calibration values of all error sources obtained by the vector calibration algorithm are shown in Figure 4.
The pose errors of the moving platform after calibration can be calculated along the trajectory in Eq. (9). As shown in Figure 5, the calibrated dynamic accuracy of the parallel mechanism has been greatly increased. In the fixed coordinate system, the position errors along the X-axis, Y-axis and Z-axis directions are reduced by 93.5%, 92.5%, and 91.7% respectively, while the angle errors around the three directions are reduced by 93.6%, 91.2%, and 86.8% respectively. It illustrates that the necessity of calibration of the parallel mechanism before it is put into work. On the other hand, the reliability of the proposed calibration algorithm has also been illustrated.
Before establishing elastodynamic modeling of parallel mechanisms, two assumptions are proposed: one is that the displacement of the mechanism obtained by elastodynamic analysis is much smaller than that of the rigid body dynamics. Second, whilst there is a coupling effect between the rigid and elastic motion of the mechanism, the coupling relationship terms between them can be ignored in terms of a mechanism with less flexibility [32].
3.1.1 Spatial Beam Element Model
The five-branch links of the parallel mechanism are identically regarded as flexible parts, while the moving platform, fixed base, modules and each motion pair are all regarded as rigid bodies. Meanwhile, the influence of clearance of the spherical pair is ignored. The flexible link is regarded as the spatial beam element, as shown in Figure 6. The coordinate system oij-xijyijzij of beam element is introduced where the subscript i and j represent the i-th branch link and the j-th element. Each element has 2 nodes where each node has 9 elastic displacement degrees of freedom. The generalized coordinate δij of the spatial beam element can be expressed as
where \(\delta_{ij1} - \delta_{ij3}\) and \(\delta_{ij10} - \delta_{ij12}\) represent element node displacements. \(\delta_{ij4} - \delta_{ij6}\) and \(\delta_{ij13} - \delta_{ij15}\) represent element node rotation angles, \(\delta_{ij7} - \delta_{ij9}\) and \(\delta_{ij16} - \delta_{ij18}\) represent element node curvatures.
×
The angular displacement around the axis is interpolated by a cubic difference function. The displacement and rotation angle in the other directions are interpolated by a quintic function. If \(W_{x} \left( {x_{ij} ,t} \right),\)\(W_{y} \left( {x_{ij} ,t} \right),\)\(W_{z} \left( {x_{ij} ,t} \right),\)\(\varphi_{x} \left( {x_{ij} ,t} \right),\)\(\varphi_{y} \left( {x_{ij} ,t} \right)\) and \(\varphi_{z} \left( {x_{ij} ,t} \right)\) are used to denote the elastic displacement and elastic angular displacement of any point in the element along x-axis, y-axis and z-axis directions, other parameters can be represented by generalized coordinate \({\varvec{\delta}}_{ij} .\)
According to the boundary conditions of the beam element and the corresponding interpolation function, the displacement functions of the beam element can be expressed as
where \({\varvec{N}}_{ij1} ,\)\({\varvec{N}}_{ij2} ,\)\({\varvec{N}}_{ij3} ,\) and \({\varvec{N}}_{ij4}\) represent the vector matrix obtained by interpolation.
where \(x_{{{\text{A}}({\text{B}})}} ,\)\(y_{{{\text{A}}({\text{B}})}}\) and \(z_{{{\text{A}}({\text{B}})}}\) represent the rigid body displacements of the element nodes A(B) along the X-axis, Y-axis and Z-axis directions. θx, θy and θz represent the rotation angle of the two element nodes around the X-axis, Y-axis and Z-axis.
Assuming that the mass of each element is concentrated on the axis, the kinetic energy of the element can be expressed as
where ρ and S are the material density and cross-sectional area of the element. Ix represents the polar inertia moment of the element cross-section along the X-axis direction.
If the shear deformation of beam element and the coupling between the axial and lateral displacement are ignored, the deformation potential energy of the spatial beam element can be expressed as
where Iy and Iz represent the polar inertia moments of the element cross-section of the element along the Y-axis and Z-axis. Kij denotes the stiffness matrix of the element.
According to the Lagrange dynamics equation [33], by applying the kinetic energy and deformation potential energy of the space beam element, the elastodynamic equation of the element in the local coordinate system can be expressed as
where Mij denotes the mass matrix of the element. Fij denotes the generalized external force term including force and torque. Pij represents the interaction force term caused by the connection of the beam element. Qij is the rigid body inertial force term.
To facilitate elastic modelling, the elastodynamic equations in the local coordinate system are converted to the base coordinate system. As shown in Figure 7, the generalized coordinates \(\overline{\user2{\delta }}_{ij}\) in the base coordinate system can be expressed as
where \(\overline{\user2{R}}_{ij} = \text {diag}\left( {{\varvec{R}}_{ij} ,{\varvec{R}}_{ij} ,{\varvec{R}}_{ij} ,{\varvec{R}}_{ij} ,{\varvec{R}}_{ij} ,{\varvec{R}}_{ij} } \right),\)\({\varvec{R}}_{ij}\) represents the transformation matrix from the local coordinate system to the base coordinate system of link.
×
From Eq. (16), the relational expressions with the first and second derivatives of \({\varvec{\delta}}_{ij}\) can be obtained
The fixed-length link is regarded as a flexible rod while the rest are assumed to be rigid parts. As shown in Figure 8, the link is divided into n elements, which are numbered 1, 2, ..., n + 1 in sequence. Each element is connected adjacently in turn. The elastic displacement of the right end of the j-th element is consistent with that of the left end of the (j + 1)-th unit, 1 ≤ j ≤ n − 1.
×
Connecting the left and right ends of the fixed-length link are spherical pairs, thereby the curvature of the end beam element is 0, that is, \(\overline{\delta }_{{\left( {i1} \right)7}} = \overline{\delta }_{{\left( {i1} \right)8}} = \overline{\delta }_{{\left( {i1} \right)9}} = 0,\)\(\overline{\delta }_{{\left( {in} \right)16}} = \overline{\delta }_{{\left( {in} \right)17}} = \overline{\delta }_{{\left( {in} \right)18}} = 0.\) Synthetically, the generalized coordinate \({\varvec{q}}_{i}\) of the link can be obtained from the displacement relationship between the elements.
By substituting Eq. (20) into Eq. (18) and taking the dot products of both sides with vector \(\overline{\user2{A}}_{ij}\) to obtain the element elastodynamic equation of the link in the base coordinate system \(\left\{ O \right\}\).
The kinematic constraint of the system is the deformation coordination condition. Compared with the five fixed-length links, the moving platform can be regarded as a rigid body due to relatively larger rigidity. In this parallel mechanism, the displacement of the hinge point of the fixed-length link connected to the moving platform is consistent with that of the corresponding point of the moving platform, as shown in Figure 9.
×
The elastic deformation of the link makes the center point of the moving platform move from the original point \(O_{D}\) to the point \(O^{\prime}_{D}\). The three position and pose changes caused by the movable platform are expressed as \(\left[ {\delta x_{D} ,\delta y_{D} ,\delta z_{D} ,\delta \alpha_{D} ,\delta \beta_{D} ,\delta \gamma_{D} } \right]\), which is abbreviated as \({\varvec{q}}_{D} = \left[ {q_{D1} ,q_{D2} ,q_{D3} ,q_{D4} ,q_{D5} ,q_{D6} } \right]\) where \(q_{D1} = \delta x_{D} ,\)\(q_{D2} = \delta y_{D} ,\)\(q_{D3} = \delta z_{D} ,\)\(q_{D4} = \delta \gamma_{D} ,\)\(q_{D5} = \delta \beta_{D}\) and \(q_{D6} = \delta \alpha_{D}\). \(\delta x_{D} ,\)\(\delta y_{D} ,\)\(\delta z_{D} ,\)\(\delta \alpha_{D} ,\)\(\delta \beta_{D}\) and \(\delta \gamma_{D}\) are small variables, which can be approximated as according to Taylor and McLaughlin Equations.
The transformation matrix from coordinate system \(\left\{ {D^{\prime} - X^{\prime}_{D} Y^{\prime}_{D} Z^{\prime}_{D} } \right\}\) to \(\left\{ {D - X_{D} Y_{D} Z_{D} } \right\}\) can be expressed as \(\Delta {\varvec{T}}\). The transformation matrix \({}_{D}^{O} \user2{T^{\prime}}\) from the coordinate system \(\left\{ {D^{\prime} - X^{\prime}_{D} Y^{\prime}_{D} Z^{\prime}_{D} } \right\}\) to the base coordinate system can be expressed as \({}_{D}^{O} \user2{T^{\prime}} = \Delta {\varvec{T}}{}_{D}^{O} {\varvec{T}}\). From the view of the moving platform, the position of each hinge point on the moving platform is always fixed. The expression of \(C^{\prime}_{i}\) in the base coordinate system can be expressed as
where \({\varvec{q}}_{Ci}\) is the elastic displacement of the hinge. \({\varvec{J}}_{Ci}\) denotes the kinematic constraint matrix. \({\varvec{q}}_{D}\) represents the pose changes of the moving platform caused by elastic deformation.
Eq. (24) is the kinematic constraint equation of the 5-PSS/UPU parallel mechanism. Meanwhile, the dynamic constraint equation needs to be meet, i.e., the external force and inertial force of the moving platform must be balanced with the force exerted by the fixed-length link on the moving platform. Ignoring the coupling relationship between the rigid body motion and elastic motion of the moving platform, the dynamic constraint equation of the moving platform can be expressed as
where \({\varvec{M}}_{D}\) is mass matrix of the moving platform. \(\user2{\ddot{q}}_{aD}\) denotes the acceleration array of the moving platform. \({\varvec{F}}_{i}\) is the combined force array of the branch-chain on the moving platform, \({\varvec{F}}_{w}\) is the external force array on the moving platform.
The dynamic constraint equation in term of \(\user2{\ddot{q}}_{aD} = \user2{\ddot{q}}_{D} + \user2{\ddot{q}}_{rD}\) can be rewritten as:
where \({\varvec{Q}}_{D} = {\varvec{F}}_{i} + {\varvec{F}}_{w} - {\varvec{M}}_{D} \user2{\ddot{q}}_{rD} .\)
3.1.4 Elastic Dynamics Equation of Parallel Mechanism System
On the basis of the kinematics and dynamics constraint relations of each component of the system, the elastodynamic equations of each link are assembled from the elastodynamic equations of each branch chain. To facilitate the analysis, a generalized coordinate of branch chain \(\hat{\user2{q}}_{i} \left( {i = 1,2,3,4,5} \right)\) is defined as
The relation equation \({\varvec{q}}_{i} = \hat{\user2{R}}_{i} \hat{\user2{q}}_{i}\) between \(\hat{\user2{q}}_{i}\) and \({\varvec{q}}_{i}\) can be obtained from the kinematics constraint relation equation. Substituting the equation into Eq. (22), the new equation is taken the dot products of both sides with vector \(\hat{\user2{R}}_{i}^{{\text{T}}}\) as
Meanwhile, to facilitate the assembly of the system equations, the generalized system coordinate \(\hat{\user2{q}}_{i}\) and \({\varvec{q}}_{i}\) can be written as
By assembling and superposing all the elastodynamic equations of the branch links as well as considering the effect of the system damping, the elastodynamic equations of the whole system in the base coordinate system can be expressed as
where \({\varvec{M}}\) is the total mass matrix of the system. \({\varvec{C}}\) is the coefficient matrix of the damping effect. \({\varvec{K}}\) is the total stiffness matrix of the system, \({\varvec{Q}}\) is the generalized force matrix of the system.
3.2 Analysis of Dynamic Accuracy
According to the force simulation results analyzed the Newton-Euler method of each rigid body component and the structure size of each component, one can know that the dynamic accuracy of the parallel mechanism is affected by the deformation of the five flexible links. Thus, the elastodynamic model is actually a rigid-flexible coupling dynamics model [34]. To verify the correctness of the elastodynamic model, the generalized forces are obtained via the co-simulation with HYPERMESH, ANSYS and ADAMS software. First, the flexible links are meshed by hexahedron elements in HYPERMESH, and the mnf files of the meshed links are obtained via ANSYS. Then, loading the link files, rigid links are replaced with flexible bodies in ADAMS. The simulation model is shown as Figure 10.
×
The structure and material parameters of the 5-PSS/UPU parallel mechanism are shown in Table 3. The external force \({\varvec{F}}_{w} = \left[ {0 \, 0 \, 500 \, 0 \, 0 \, 0} \right]\) is imposed on the center of the moving platform. The motion trajectory of the moving platform is given in Eq. (32). The solution time and solution integration step are set to \(t = 2\;{\text{s}}\) and \(\Delta t = 0.001\;{\text{s}}{.}\)
Structure parameters of 5-PSS/UPU parallel mechanism
Parameter name
Value
Link length LBC (mm)
560
Link material density \(\rho_{BC}\) (kg·m−3)
2.7 × 103
Cross-sectional area of link SBC (mm−2)
400π
Elastic modulus of link EBC (Pa)
0.7 × 1011
Link shear modulus GBC (Pa)
2.7 × 1010
Mobile platform quality mD (kg)
20
The actuator displacements are obtained by substituting the motion and dynamic constraints into the deformation equation, which is used as the input of the simulation model to obtain the actuator forces. The comparison between theoretical actuator forces calculated via Eq. (31) and that of simulation is shown in Figure 11. One can find that the errors of the actuator force of the theoretical value and the simulation value are less than 4%, which proves the correctness of the rigid-flexible coupling dynamic model. The main reason for this error is that the number and form of the unit division of the simulation are different from the theory.
×
The Newmark method [35] is used to calculate the position and pose errors of the moving platform caused by the elastic deformation of the branch rod, as shown in Figure 12.
×
Obviously, it can be seen from Figures 12 and 13 that violent oscillations of the pose of the moving platform are emerged due to the elastic deformation of the branch link. The dynamic accuracy of the moving platform is greatly affected because of these oscillations. When the time t = 1.772 s and t = 1.264 s, the maximum displacement error occurs along the X-axis and Y-axis directions and the Z-axis direction. At the time t = 1.791 s and t = 1.248 s, the maximum angle error arises in the β and γ direction.
×
To quantitatively analyze the influence of factors, such as the cross-sectional area of the branch link, the elastic modulus and the mass of the moving platform on the dynamic accuracy of the flexible parallel mechanism, the evaluation of above factors is obtained by calculating the dimensionless root mean square error [36]. The influence index of dimensionless root mean square error can be written as
where xai represents the output of the moving platform in real condition, xi denotes the output of the moving platform in ideal condition. \(RMS(x_{ai} - x_{i} )\) represents the root mean square error of the output of the moving platform in real condition. \(RMS(x_{i} )\) represents the root mean square error of the output of the moving platform in ideal condition. N is the simulated sample size.
To make the results more intuitive and representative, the dimensionless root mean square error influence index of the displacement, velocity and acceleration in the Z-axis direction of the centroid of the moving platform will be calculated. It can be seen from Eq. (33) that the dynamic accuracy is proportional to the dimensionless root mean square error. In terms of the different conditions of the cross-sectional area, elastic modulus and moving platform mass of the branch link, the quantitative calculation of the non-dimensional root mean square error of the output of the parallel mechanism is shown in Figure 14.
×
Figure 14(a) shows that the non-dimensional root-mean-square error of the position, velocity and acceleration of the moving platform of the parallel mechanism are proportional to the cross-sectional area. When the cross-sectional area increases from 400π mm2 to 900π mm2, the dimensionless root-mean-square error influence indexes of displacement, velocity and acceleration decrease from 0.0284%, 5.6235% and 59.6772% to 0.0019%, 0.8277%, and 8.6590%, respectively. It shows that the larger cross-sectional area of the branch rod corresponds to the smaller output error of the mechanism and the higher dynamic accuracy.
Similarly, the non-dimensional root-mean-square error of the position, velocity and acceleration of the moving platform of the parallel mechanism are proportional to the elastic modulus, as shown in Figure 14(b). When the elastic modulus increases from 70 GPa to 206 GPa, the dimensionless root-mean- square error influence indexes of displacement, velocity, and acceleration decrease from 0.0284%, 5.6235% and 59.6772% to 0.0029%, 0.7950% and 20.0719%, respectively. It illustrates that the larger elastic modulus of the branch rod corresponds to the smaller output error of the mechanism and the higher dynamic accuracy.
In Figure 14(c), the non-dimensional root-mean-square error of the position, velocity and acceleration of the moving platform of the parallel mechanism are proportional to the mass of moving platform. When the mass of moving platform increases from 20 kg to 60 kg, the dimensionless root-mean-square error influence indexes of displacement, velocity, and acceleration increase from 0.0284%, 5.6235% and 59.6772% to 0.0708%, 13.6946% and 124.250%, respectively. It shows that the greater mass of the moving platform corresponds to the greater the output error of the mechanism, the more unstable the vibration amplitude of the mechanism and the lower dynamic accuracy.
4 Conclusions
Taking a 5-PSS/UPU parallel mechanism as an example, on the basis of an error model and the mapping law of geometric error to the dynamic accuracy, a vector calibration algorithm was proposed to reduce the position and pose error along the whole motion trajectory. Then, the elastic dynamic model was established via analyzing the elastic deformation of the components. Furthermore, the effect of the flexibility of the components on the dynamic accuracy of the parallel mechanism was analyzed.
(1)
The influence of each error source on the dynamic accuracy of the parallel mechanism is analyzed based on the geometric error model. After the main error sources of calibration with the closed-loop vector method, the position error along the x-axis, y-axis, and z-axis directions are reduced by 93.5%, 92.5%, 91.7% respectively, while the angle errors around the x-axis, y-axis, and z-axis directions are reduced by 93.6%, 91.2%, and 86.8% respectively. It shows that the dynamic accuracy of the parallel mechanism can be improved via reasonable compensation of geometric errors.
(2)
The elastic dynamics equation of the parallel mechanism is established by combining the finite element method with Lagrange method, which is solved by the Newmark direct integration method. Furthermore, the correctness of the rigid-flexible coupling dynamic model is verified by the co-simulation with HYPERMESH, ANSYS and ADAMS software.
(3)
Numerical simulation results show that the cross-sectional area of the branch connecting rod and the elastic modulus are proportional to the dimensionless root mean square error of the output of the moving platform, while the mass of the moving platform is inverse proportional to the dimensionless root mean square error of the output of the moving platform. With the requirements of rigidity and assembly, a reasonable parameter combination can effectively improve the dynamic accuracy of the mechanism.
Acknowledgements
Not applicable.
Competing Interests
The authors declare no competing financial interests.
Open AccessThis article is licensed under a Creative Commons Attribution 4.0 International License, which permits use, sharing, adaptation, distribution and reproduction in any medium or format, as long as you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons licence, and indicate if changes were made. The images or other third party material in this article are included in the article's Creative Commons licence, unless indicated otherwise in a credit line to the material. If material is not included in the article's Creative Commons licence and your intended use is not permitted by statutory regulation or exceeds the permitted use, you will need to obtain permission directly from the copyright holder. To view a copy of this licence, visit http://creativecommons.org/licenses/by/4.0/.