Next Article in Journal
Robotic Development for the Nuclear Environment: Challenges and Strategy
Next Article in Special Issue
Functional Design of a 6-DOF Platform for Micro-Positioning
Previous Article in Journal
Differential Facial Articulacy in Robots and Humans Elicit Different Levels of Responsiveness, Empathy, and Projected Feelings
Previous Article in Special Issue
A Novel 3-URU Architecture with Actuators on the Base: Kinematics and Singularity Analysis
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

The Effect of the Optimization Selection of Position Analysis Route on the Forward Position Solutions of Parallel Mechanisms

School of Mechanical Engineering, Changzhou University, Changzhou 213164, China
*
Author to whom correspondence should be addressed.
Robotics 2020, 9(4), 93; https://doi.org/10.3390/robotics9040093
Submission received: 13 October 2020 / Revised: 4 November 2020 / Accepted: 11 November 2020 / Published: 13 November 2020
(This article belongs to the Special Issue Kinematics and Robot Design III, KaRD2020)

Abstract

:
The forward position solution (FPS) of any complex parallel mechanism (PM) can be solved through solving in sequence all of the independent loops contained in the PM. Therefore, when solving the positions of a PM, all independent loops, especially the first loop, must be correctly selected. The optimization selection criterion of the position analysis route (PAR) proposed for the FPS is presented in this paper, which can not only make kinematics modeling and solving efficient but also make it easy to get its symbolic position solutions. Two three-translation PMs are used as the examples to illustrate the optimization selection of their PARs and obtain their symbolic position solutions.

1. Introduction

The forward position solution (FPS) of a PM is one of the most important and basic problems in the parallel mechanisms (PMs) research community.
At present, most researchers use the loop vector method [1,2,3] to establish the input–output position equations of parallel mechanism (PM) and then use numerical or algebraic methods to find its solutions. The numerical method is used directly to solve the position equations, whose advantage is that the real number solutions can be obtained, and the disadvantage is that the iteration is easy to diverge and large calculations are needed. The algebraic methods [4,5,6,7], by eliminating the unknowns in the position equations, finally express it as a one-variable higher-order equation, from which all possible solutions can be found. However, algebraic methods need advanced mathematical elimination methods.
It is noticed that the establishment of the above-mentioned position equations of a PM based on the loop vector method does not consider the effect of topological characteristics [8,9] of the PM on its kinematics. For the loop vector method, on the one hand, the loop that some researchers use is a mostly “nature loop” but not actual independent loop. On the other hand, all loops are treated as having equal “ranking status”. Therefore, there exist more variables contained in the position equations. Especially when the algebraic method is used, the mathematical elimination processes take more time and are complicated.
For PMs with the same topology of branch chains, there is no need for selecting the optimal position analysis route (PAR). However for PMs with branch chains of different topology, the correct selection of the PAR is necessary, which will affect the efficiency of the FPS and even the solution forms of the forward position (i.e., numerical, closed-form, symbolic). If the PAR is not selected properly, the process of FPS of PMs may be more complicated and difficult, and even their symbolic solutions cannot be obtained. On the contrary, the process of the FPS is convenient, and their symbolic position solutions can be obtained as much as possible.
It can be seen from Ref. [9,10] that the FPS of a PM can be performed by handling its sub-kinematic chains included in the PM in an orderly manner, while an SKC can be solved in accordance with the order of the contained independent loops. Then, for PMs with branch chains of different topologies, the problem of how to sequentially select the first, the 2nd, …, v-th independent loops, especially the first loop, will become the key to solving FPS. This problem will directly affect whether the kinematics modeling and FPS can be carried out smoothly.
Through previous work [10,11], the authors find that (1) based on the “principle of least constraint degree” [8,9], there may be multiple topological structure decomposition schemes, which are not all the best PAR. (2) If the PAR is not selected properly, it may make the FPS complicated or impossible. Otherwise, the FPS is simple and convenient, and the symbolic position solutions can be obtained as much as possible. These observations lead the investigation of the paper.
The remainder of the paper is organized as follows. In Section 2, optimization criteria and procedures of optimization selection of PAR are presented. In Section 3, a group of basic formulas of the topological characteristic index used for topological property analysis [12] is described. Two three-translation (3T) PMs with branch chains of different topologies are used as examples to illustrate the optimization selection of PAR and their effect on the efficiency of the FPS and on the symbolic position solutions in Section 4, respectively. Finally, conclusions are drawn in the last part.

2. The Optimization Selection Criteria for the Position Analysis Route (PAR)

2.1. Optimization Criteria for PAR

In the FPS of the PMs, the principle of the minimum constraint degree [8,9] ∆min and the minimum number of independent displacement equations (NIDE) ξmin should be satisfied at the same time when selecting an optimal PAR. Once choosing the optimal PAR correctly, the FPS can be carried out efficiently, and its symbolic position solutions can be obtained as much as possible.

2.2. Procedures of Optimization Selection of PAR

i.
For all loops inside the sub-kinematic chains (SKC) [9] of a PM, the loop with the smallest constraint degree value (Δ ≥ 0) should be used as the first loop for the FPS, which can minimize the number of virtual variables [10] that should be assigned when performing FPS to the smallest degree.
ii.
If there are several optional first loops with the same minimum constraint degree Δ, the loop with the smallest of the NIDE ξmin should be selected as the first loop. In this way, the number of position equations required to solve the loop positions can be minimized, which is exactly equal to ξmin.
iii.
If there are both planar SKC(s) and space SKC(s) in a PM, the FPS should be started from the planar SKC(s) first, and then the space SKC(s) should be analyzed. This is because the NIDE of the planar mechanism loop is always the smallest, i.e., ξ = 3.
The above-mentioned criteria and procedures of optimization selection of PAR will be applied to explain the optimization selection of PAR and their effect on the efficiency of the FPS and on the symbolic position solutions of the two three-translation (3T) PMs with branch chains of different topology.

3. Basic Formulas for Topological Characteristics Analysis

3.1. Analysis of the POC Set

The position and orientation characteristic (POC) set equations for the serial mechanism and parallel mechanism are expressed as respectively:
M b i = i = 1 m M J i
M P a = i = 1 n M b i
where
  • M J i —POC set generated by the ith joint.
  • M b i —POC set generated by the end link of the ith chain.
  • M P a —POC set generated by the moving platform of PM.

3.2. Determining the DOF

The proposed general and full-cycle degrees of freedom (DOF) formula for PMs is given below:
F = i = 1 m f i i = 1 v ξ L j
ξ L j = dim . { ( i = 1 j M b i M b ( j + 1 ) }
where
  • F—DOF of PM.
  • fi—DOF of the ith joint.
  • v—number of independent loops, and v = m − n + 1.
  • m, n—number of all joints and links of the whole PM, respectively.
  • ξ L j —number of independent displacement equations (NIDE) of the jth loop.
  • i = 1 j M b i —POC set generated by the sub-PM formed by the former j branches.
  • M b ( j + 1 ) —POC set generated by the end link of (j + 1)th sub-chains.

3.3. Determining the Coupling Degree

According to the mechanism composition principle based on single-opened-chains (SOC) units, any PM can be decomposed into groups of SKC, and an SKC with v independent loops can be decomposed into v SOC. The constraint degree, denoted as △j, of the jth SOC is defined by:
Δ j = i = 1 m j f i I j ξ L j = { Δ j = 5 , 4 , 2 , 1 Δ j 0 = 0 Δ j + = + 1 , + 2 , + 3 ,
where
  • m j —number of joints contained in the jth SOCj.
  • I j —the number of actuated joints in the jth SOCj.
For an SKC, the following equation must be satisfied:
j = 1 v Δ j = 0
Then, the coupling degree of an SKC is expressed as:
k = | Δ j | = Δ j + = 1 2 min { j = 1 v | Δ j | }
Here, min { } operation means that the decomposition sequence with the smallest j = 1 v | Δ j | should be selected.
The constraint degree of the jth SOC indicates the constraint influences of the chain on the kinematic performance of the mechanism. Its physical meaning will be explained below.
(a) An SOC with a negative constraint degree, denoted as SOC, will apply | Δ j | constraint equations to a mechanism, and the number of DOF of the mechanism will be decreased by DOFs of | Δ j | .
(b) An SOC with a positive constraint degree, denoted as SOC+, will increase the number of DOF of the mechanism by Δ j + . Therefore, its forward kinematics solutions could not be solved immediately. Its assembly can be determined only on the condition that Δ j + virtual variables are assigned. When the number of the virtual variables is equal to the number of | Δ j | constraint equations applied in SOC, i.e., k = | Δ j | = Δ j + , the motion of the mechanism is defined, and its forward kinematics can be obtained.
(c) An SOC with zero constraint degree, denoted as SOC0, does not affect the DOF. Its forward kinematics solutions can be obtained immediately without assigning virtual variables.
Therefore, the coupling degree k describes the complexity level of the topological structure of a PM, and it also represents the complexity level of its kinematic and dynamic analysis. The lower the coupling degree k, the easier the treatment of its forward kinematic and dynamic analysis [9,10].
The detailed explanations for these concepts and notations of topological characteristic index used for topological property analysis can be found in Ref. [9,12].

4. Case Studies

4.1. Three-Translation PM (3T-CU)

The three-translation PM proposed by authors [13], denoted as 3T-CU, as shown in Figure 1a, consists of a base platform 0, a moving platform 1, and three different branch chains. Among them, the first branch is R11//R21//C31, which is connected to the base platform 0 through the revolute joint R11 and connected to the moving platform 1 through the cylindrical joint C31. The second branch is R12-U22-U32, which is connected to the base platform 0 through the revolute joint R12 and connected to the moving platform 1 through the moving joint U32. The third branch is a hybrid branch chain, which includes a parallelogram, and its two ends are respectively connected to the base platform 0 and the moving platform 1 through revolute joints R13 and R33. Here, R11, R12, and R13 on the base platform 0 could be the actuated joints.

4.1.1. Topology Analysis

(i) Analysis of the POC Set
Obviously, the topological architecture of chain I, II, and III of the PM can be denoted as, respectively:
SOC1:{R11//R21//C31}, SOC2:{R12-U22-U32}, SOC3:{R13//R23(Pa(4R))//R33}.
Here, symbol “//” stands for “parallel”, while symbol “-“ stands for no special geometrical relation, which applies to the whole context of the paper.
The POC sets of the end of the three SOCS are determined according to Equation (1) as follows, respectively.
M S O C 1 = [ t 3 r 1 ( | | R 11 ) ]   ,   M S O C 2 = [ t 3 r 2 ]   ,   M S O C 3 = [ t 3 r 1 ( | | R 13 ) ] .
The POC set of the moving platform of this PM is determined from Equation (2) by
M p a = M S O C 1 M S O C 2 M S O C 3 = [ t 3 r 1 ( | | R 11 ) ] [ t 3 r 2 ] [ t 3 r 1 ( | | R 13 ) ] = [ t 3 r 0 ] .
Hence, the moving platform 1 of the PM has a three-translation motion output.
(ii) Determining the DOF
It is easy for this PM to have two selection methods for PAR, as follows,
Case ①: If the first loop of the PM (that is, sub-PM) consists of the first and third branch chains, namely R11//R21//C31-R33//(Pa(4R))R23//R13, the number of independent displacement equations (NIDE) is obtained by Equation (4)
ξ L 1 = dim { [ t 3 r 1 ( | | R 11 ) ] [ t 3 r 1 ( | | R 13 ) ] } = dim { [ t 3 r 2 | | ( ( R 11 , R 13 ) ) ] } = 5 .
From Equation (3), the degree of freedom (DOF) of the first loop (1st sub-PM) is:
F ( 1 2 ) = f ξ L 1 = ( 4 + 4 ) 5 = 3 .
The second loop is composed of the above-mentioned sub-PM and the second branch chain. From Equation (4), the NIDE is calculated by
ξ L 2 = dim { [ t 3 r 1 ( | | R 11 ) ] [ t 3 r 1 ( | | R 13 ) ] [ t 3 r 2 ] } = dim { [ t 3 r 2 ] } = 5 .
Case ②: If the first loop (sub-PM) of the PM consists of the second and the third branch chains, namely R12-U22-U32-R33//(Pa(4R))R23//R13, the NIDE is obtained by Equation (4):
ξ L 1 = dim { [ t 3 r 2 ] [ t 3 r 1 ( | | R 13 ) ] } = dim { [ t 3 r 2 ] } = 5 .
From Equation (3), the degree of freedom of the first loop (1st sub-PM) is:
F ( 1 2 ) = f ξ L 1 = ( 5 + 4 ) 5 = 4 .
The second loop is composed of the above-mentioned 1st sub-PM and the first branch chain. From Equation (4), the number of independent displacement equation is:
ξ L 2 = dim { [ t 3 r 2 ] [ t 3 r 1 ( | | R 13 ) ] [ t 3 r 1 ( | | R 11 ) ] } = dim { [ t 3 r 2 ( | | ( R 11   ,   R 13 ) ] } = 5 .
Thus, the DOF of the PM is calculated from Equation (3) as:
F = i = 1 m f i i = 1 v ξ L j = ( 8 + 5 ) ( 5 + 5 ) = 3 .
Therefore, when the revolute joints R11, R12, and R13 on the base platform 0 are selected as the actuated joints, the moving platform 1 can realize 3T motion outputs.
(iii) Determining the coupling degree
Form Equation (5), the constraint degree of the two loops are respectively given by:
For   Case   :   Δ 1 = i = 1 m 1 f i I 1 ξ L 1 = 8 2 5 = + 1 , Δ 2 = i = 1 m 2 f i I 2 ξ L 2 = 5 1 5 = 1 .
From Equation (6), the PM contains one SKC. Further, from Equation (7), the coupling degree of the SKC is given by
κ = 1 2 min { j = 1 v | Δ j | } = 1 2 ( | + 1 | + | 1 | ) = 1 .
Therefore, the coupling degree of the PM is κ = 1, which means that one virtual variable needs to be assigned when solving its positions.
For   Case     Δ 1 = i = 1 m 1 f i I 1 ξ L 1 = 9 2 5 = + 2 , .   Δ 2 = i = 1 m 2 f i I 2 ξ L 2 = 4 1 5 = 2 .
From Equation (6), the PM contains one SKC. Furthermore, from Equation (7), the coupling degree of the SKC is given by
κ = 1 2 min { j = 1 v | Δ j | } = 1 2 ( | + 2 | + | 2 | ) = 2
This moment, the coupling degree of the PM is κ = 2, which means that two virtual variables need to be assigned when solving its positions, and it undoubtedly makes the FPS much more complicated than the case ① with only one virtual variable.
(iv) Optimization selection for PAR
So far, it can be found that according to the cases ① and ②, the NIDE of the two cases obtained are the same, i.e., ξL1 = ξL2 = 5, but their constraint degree ∆ (or coupling degree κ) is different, i.e., κ of the case ① is one, while κ of the case ② is two. Therefore, according to the optimization criteria for the PAR, the case ① that has the smallest constraint degree value (∆min = 1) and the minimum NIDE (ξmin = 5) should be used to solve the FPS. The details are described below.

4.1.2. Position Analysis

(i) The coordinate system and parameterization
The kinematic modelling of the PM is shown in Figure 1b. The base platform 0 is an equilateral triangle with a circle radius R, and select the geometric center O as the origin of the base coordinate system. The x- and y-axis are perpendicular and parallel to the line OA2. Let moving platform 1 be an equilateral triangle with a circle radius r, and select the O’ point on the moving platform as the origin of the moving coordinate system. The x’- and y’-axis are perpendicular and parallel to the line O’C2. The z and z’ axis are determined by the Cartesian coordinate rule.
Let the angle θi between vectors AiBi and AiO be the input angle, and the length of the line AiBi and BiCi (i = 1–3) is equal to l1 and l2, respectively.
(ii) Direct kinematics
To perform the FPS, i.e., it is to compute the position O’(x, y, z) of the moving platform with the known actuated joints θ1, θ2, and θ3.
The coordinates of points Ai and Bi (i = 1–3) are easily known as:
A 1 = ( R cos 30 ° , R sin 30 ° , 0 ) T , A 2 = ( 0 , R , 0 ) T , A 3 = ( R cos 30 ° , R sin 30 ° , 0 ) T , B 1 = ( ( R l 1 cos θ 1 ) cos 30 ° , ( R l 1 cos θ 1 ) sin 30 ° , l 1 sin θ 1 ) T , B 2 = ( 0 , R l 1 cos θ 2 , l 1 sin θ 2 ) T , B 3 = ( ( R l 1 cos θ 3 ) cos 30 ° , ( R l 1 cos θ 3 ) sin 30 ° , l 1 sin θ 3 ) T .
① Solving the first loop (A1-B1-C1-C3 -B3-A3) with a positive constraint (∆1 = 1)
Since the coupling degree of the PM is 1, it is necessary to assign one virtual variable when performing the FPS. Let the angle α1 between B1C1 and B1D1 be the virtual variable, where B1D1//A1O. It is easy to know that the coordinates of point C1 are below:
C 1 = ( x B 1 l 2 cos 30 ° cos α 1   ,   y B 1 + l 2 sin 30 ° cos α 1   ,   z B 1 + l 2 sin α 1 ) T .
Thus, the three points Ci(i = 1–3) in the base coordinate system are calculated as:
C 1 = ( r cos 30 ° + x ,   r sin 30 ° + y ,   z ) T
C 2 = ( x ,   r + y ,   z ) T
C 3 = ( r cos 30 ° + x ,   r sin 30 ° + y ,   z ) T .
From Equations (9) and (11), we can get:
C 3 = ( x B 1 l 2 cos 30 ° cos α 1 2 r cos 30 °   ,   y B 1 + l 2 sin 30 ° cos α 1   ,   z B 1 + l 2 sin α 1 ) T .
Due to the length constraint defined by B3C3 = l2, we can get:
α 1 = 2 arctan ( G 2 ± G 2 2 + G 1 2 G 3 2 G 3 G 1 )
where
p = x B 1 2 r cos 30 ° x B 3 ,   q = y B 1 y B 3 ,   g = z B 1 z B 3 ,   G 1 = 2 l 2 ( q sin 30 ° p cos 30 ° ) ,   G 2 = 2 g l 2 ,   G 3 = p 2 + q 2 + g 2 .
Substituting Equation (13) into Equations (8) and (12), the points C1 and C3 can be obtained.
② Solving the second loop (Loop2: A2-B2-C2) with negative constraint (∆2 = −1)
After the positions of all joints on the first loop are obtained, it is easier to solve that on the second loop. From Equations (9) and (10), the coordinates of point C2 are:
C 2 = ( x C 1 r cos 30 °   , y C 1 + r + r sin 30 °   , z C 1 ) T .
Therefore, the origin coordinates of the moving platform can be easily obtained.
It can be seen that from FPS of the PM there is a total of five position equations, i.e., (1) three geometric constraint equations: B1C1 = l2, B3C3 = l2, y C 3 = y C 1 ; (2) two topological constraint equations introduced by the POC feature (3T): z C 2 = z C 1 , z C 3 = z C 1 , which are exactly equal to the NIDE ξL = 5, and we ensure that the positions of the PM can be solved.
The inverse kinematics of this PM is omitted here due to its easiness.
(iii) Verification
Set the parameters of the PM as R = 90, r = 55, l1 = 40, l2 = 40(unit: mm), and the input angles of the three actuated joints are θ1 = 30°, θ2 = 60°, and θ3 = 60°.
From Equations (8)–(14), two sets of real solutions are obtained, i.e., (1) x = −33.9339, y = 19.5917, z = 13.9672, and (2) x = 23.5901, y = −13.6197, and z = 49.6216. It has been verified that both the FPS and inverse solutions derived above are correct.
The authors also analyze the position of the 3T-CU PM according to case ②, but only numerical solutions were obtained, and calculations are more complicated.
So far, for route selection cases ① and ②, the NIDE are ξ L 1 = ξ L 2 = 5 , but the constraint degree of case ① is Δ 1 = + 1 , Δ 2 = 1 and the constraint degree of case ② is Δ 1 = + 2 , Δ 2 = 2 . Therefore, case ① is the optimization selection for PAR. It not only guarantees the efficient kinematic modeling but also obtains the symbolic solutions.

4.2. Three-Translation PM (Delta-CU)

Figure 2a shows another three-translation PM [14,15], denoted as Delta-CU PM, designed by the authors, which consists of base platform 0, moving platform 1, and three branch chains. Among them, the first and third ones are hybrid branches containing a parallelogram structure (same as the traditional Delta mechanism). The first and third branches are connected to the base platform 0 through the revolute joints R11 and R13, and they are connected to the moving platform 1 through the revolute joints R31 and R33, respectively. The second branch is R12-U22-U32, and its two ends are connected to base platform 0 and moving platform 1 through R12 and U32, respectively. The PM is called Delta-CU, i.e., 2-R//R//Pa//R+R-U-U.
Compared with the Delta mechanism with the same three branches (all of which are hybrid branches with a parallelogram structure), this Delta-CU mechanism decreases two revolute joints and three links, and hence the structure is simpler. Since the topological structure of the three branch chains are not all different, it involves the problem of optimization selection of PAR, and different PARs will lead to a big difference in the difficulty of the FPS of the PM.

4.2.1. Topological Analysis

(i) Analysis of the POC Set
The first and third mixed branches are denoted as SOCi {R1i//R2i//Pa(4R)-R3i}(i = 1, 3), while the second branch is denoted as SOC2{R12-U22-U42}.
The POC sets of the end of the three SOCS are determined according to Equation (1) as follows, respectively:
M SOC 1 = [ t 3 r 1 ( | | R 11 ) ]   ,   M SOC 2 = [ t 3 r 2 ]   ,   M SOC 3 = [ t 3 r 1 ( | | R 13 ) ]
The POC set of the moving platform of this PM is determined from Equation (2) by:
M p a = M S O C 1 M S O C 2 M S O C 3 = [ t 3 r 1 ( | | R 11 ) ] [ t 3 r 2 ] [ t 3 r 1 ( | | R 13 ) ] = [ t 3 r 0 ]
Hence, the moving platform 1 of the PM has three-translation motion output.
(ii) Determining the DOF
The PM has three branches; therefore, it contains two independent loops. Since the three branches belong to two different topological structures, that is, the first and third branches are hybrid branches with four degrees of freedom (DOF) (one 4R parallelogram mechanism is equivalent to one prismatic joint). The DOF of the second branch is 5. Therefore, there are at least two schemes in the topology decomposition of the PM as follows.
Case ①: The first loop (sub-PM) is composed of the first and third hybrid branch chains with the least degree of freedom (DOF = 4), while the second loop is composed of the sub-PM and the second branch (R12-U22-U32) with 5-DOF.
Case ②: The first loop (sub-PM) is composed of the first branch chain with 4-DOF and the second branch chain with 5-DOF, while the second loop is composed of the sub-PM and the third branch chain with 4-DOF.
For Case ①: The NIDE of the two loops can be obtained by Equation (4):
ξ L 1 = dim { [ t 3 r 1 ( | | R 11 ) ] [ t 3 r 1 ( | | R 13 ) ] } = dim { [ t 3 r 2 ] } = 5 , ξ L 2 = dim { [ t 3 r 1 ( | | R 11 ) ] [ t 3 r 1 ( | | R 13 ) ] [ t 3 r 2 ] } = dim { [ t 3 r 2 ] } = 5 .
From Equation (3), the DOF of the PM is:
F = i = 1 m f i i = 1 v ξ L j = ( 8 + 5 ) ( 5 + 5 ) = 3 .
Therefore, when the revolute joints R11, R12, and R13 on the base platform 0 are selected as the actuated joints, the moving platform 1 can realize 3T motion outputs.
For Case ②: The NIDE of the two loops can be obtained by Equation (4):
ξ L 1 = dim { [ t 3 r 1 ] [ t 3 r 2 ] } = dim { [ t 3 r 3 ] } = 6 , ξ L 2 = dim { [ t 3 r 1 ] [ t 3 r 2 ] [ t 3 r 1 ] } = dim { [ t 3 r 1 ] } = 4 .
From Equation (3), the DOF of the PM is:
F = i = 1 m f i i = 1 v ξ L j = ( 4 + 5 + 4 ) ( 5 + 5 ) = 3 .
The DOF of the PM is still three. Therefore, when R11, R12, and R13 on the base platform are actuated joints, the moving platform 1 can realize 3T motion outputs.
(iii) Determining the coupling degree
Case ①: From Equation (5), the constraint degrees of the two loops are respectively given by:
Δ 1 = i = 1 m 1 f i I 1 ξ L 1 = ( 4 + 4 ) 2 5 = + 1 , Δ 2 = i = 1 m 2 f i I 2 ξ L 2 = 5 1 5 = 1 .
From Equation (6), the PM contains one SKC. Furthermore, from Equation (7), the coupling degree of the SKC is given by:
k = 1 2 min { j = 1 v | Δ j | } = 1 2 ( | + 1 | + | 1 | ) = 1 .
The above equation shows the following: ① This PM contains only one SKC, and its coupling degree is one. When performing FPS, it is necessary to assign one virtual variable on the first loop with the constraint degree of positive one, and it is necessary to establish a constraint position equation containing the virtual variable on the second loop with a constraint degree of minus one. ② Since the three actuated joints are in one SKC, according to the input–output (I-O) motion decoupling determination principle [9], it can be determined that the PM does not have an input–output (I-O) motion decoupling property.
For Case ②: From Equation (5), the constraint degrees of the two loops are respectively given by:
Δ 1 = i = 1 m 1 f i I 1 ξ L 1 = ( 4 + 5 ) 2 6 = + 1 , Δ 2 = i = 1 m 2 f i I 2 ξ L 2 = 4 1 4 = 1 .
From Equation (6), the PM contains one SKC. Furthermore, from Equation (7), the coupling degree of the SKC is calculated as:
k = 1 2 min { j = 1 v | Δ j | } = 1 2 ( | + 1 | + | 1 | ) = 1 .
Of course, the topology decomposition scheme ② of the first loop of the PM can also be composed of the second and third branches, while the second loop is composed of the sub-PM and the first branch, and the result is identical.
(iv) Optimization selection for PAR
Comparing the topological decomposition Cases ① and ②, it can be seen that if the position analysis is performed according to Case ②, the constraint degree of the two loops are Δ1 = 1 and Δ2 = −1, and the NIDEs are ξL1 = 6, ξL2 = 4, respectively, which means that when performing the FPS, six position constraint equations must be found in the first loop. Obviously, the difficulty will increase, and it will even not be solved. On the contrary, if the position analysis is carried out according to Case ①, the constraint degrees of the two loops are Δ1 = 1, Δ2 = −1, and the NIDEs are ξL1 = 5 and ξL2 = 5, respectively, which means that when performing the FPS, only five position constraint equations are needed to be found in the first loop, which is obviously easier.
Therefore, when performing the FPS of the Delta-CU PM, the PAR should be selected as Case ①.

4.2.2. Position Analysis

(i) The coordinate system and parameterization
The kinematic modeling of the Delta-CU PM is shown in Figure 2b. The base platform 0 is an equilateral triangle with a circle radius R, and select the geometric center O as the origin of the base coordinate system. The x- and y-axis are perpendicular and parallel to the line OA2. Let moving platform 1 be an equilateral triangle with a circle radius r, and select the O’ point on the moving platform as the origin of the moving coordinate system. The x’- and y’-axis are perpendicular and parallel to the line OC2. The z- and z’-axis are all determined by the Cartesian coordinate rule. Let the angle θi between vectors AiBi and AiO be the input angle, and the lengths of the lines AiBi and BiCi (i = 1–3) are equal to l1 and l2, respectively. Let the coordinates of the origin of the moving coordinate system be O’ (x, y, z).
(ii) Direct kinematics
To perform the FPS, compute the position O’ = (x, y, z*) of the platform with the known actuated joints θ2, θ2, and θ3.
Since the coupling degree of the PM is κ = 1, one virtual variable needs to be assigned. Furthermore, the first loop passes through the moving platform 1, and there are two methods for selecting virtual variables, namely method A (i.e., the virtual variable starts from one side of the loop) and method B (i.e., the virtual variable starts from the moving platform) [16]. Since method B has the advantages of a short calculation path, fewer calculations, and available symbolic solutions [16], method B is now used for the calculation of the PM.
Since the PM is a 3T PM and the coupling degree is κ = 1, take one of the position parameters (x, y, z*) of the platform 1, for example, z*, as a virtual variable.
① Solving the first loop with the positive constraint (∆1 = 1)
The coordinates of Ci point (i = 1–3) on the moving platform are given, respectively.
C 1 = ( r cos 30 ° + x , r sin 30 ° + y , z * ) T , C 2 = ( x , r + y , z * ) T , C 3 = ( r cos 30 ° + x , r sin 30 ° + y , z * ) T .
Due to the length constraint defined by BiCi = l2 (i = 1, 3), we can get:
( x + m ) 2 + ( y + n ) 2 + ( z * z B 1 ) 2 = l 2 2
( x + u ) 2 + ( y + v ) 2 + ( z * z B 3 ) 2 = l 2 2
where
m = r cos 30 ° x B 1 , n = ( r sin 30 ° + y B 1 ) , u = ( r cos 30 ° + x B 3 ) , v = ( r sin 30 ° + y B 3 ) .
② Solve the second loop with the negative constraint (∆2 = −1)
Due to the length constraint defined by B2C2 = l2, we can get:
( x x B 2 ) 2 + ( y + t ) 2 + ( z * z B 2 ) 2 = l 2 2
where t = r y B 2 .
From Equations (15)–(17), we can get the symbolic solutions as follows:
{ x = N z * + D y = H z * + K z * = C 2 ± C 2 2 4 C 1 C 3 2 C 1
where
M = m 2 + n 2 + z B 1 2 x B 2 2 t 2 z B 2 2 2 , T = m 2 + n 2 + z B 1 2 u 2 v 2 z B 3 2 2 M ( m u ) m + x B 2 , P = 2 ( m u ) ( t n ) m + x B 2 + 2 ( n v ) , Q = 2 ( m u ) ( z B 1 z B 2 ) m + x B 2 + 2 ( z B 3 z B 1 ) , H = Q P ,   K = T P   , N = ( n t ) H + ( z B 2 z B 1 ) x B 2 + m ,   D = ( n t ) K + M x B 2 + m , C 1 = N 2 + H 2 + 1 ,   C 2 = 2 ( N D + H K + m N + n H z B 1 ) ,   C 3 = D 2 + K 2 + 2 m D + 2 n K + m 2 + n 2 + z B 1 2 l 2 2 .
It can be seen that from the FPS of the PM there is also a total of five position equations in the first loop, i.e., ① two position constraint equations z C 1 = z C 3 = z introduced by the topological constraint that the moving platform 1 always performs three-dimensional translation, ② two length constraint conditions B1C1 = l2 and B3C3 = l2, and ③ the position of C2 is also constrained by the length constraint equation B2C2 = l2 inside the second loop. In this way, there are five position constraint equations, which are equal to the NIDE ζL = 5. Therefore, the position of the first loop is guaranteed to be solvable, since these position equations are nonlinear ones and simper, symbolic solutions can be easily obtained.
The inverse kinematics of this PM and numerical verification are omitted here due to its easiness.

5. Conclusions

The optimization selection for PAR can affect the effectiveness of FPS and the solution forms. For this reason, the optimization selection criteria for PAR are proposed, i.e., when solving the position, the loop should be selected according to the criteria of “minimum constraint degree value (∆min) and minimum number of independent displacement equations (ξmin)” in order to effectively perform FPS and obtain the symbolic solutions to the greatest possible extent. Otherwise, the FPS may be difficult, complicated, or symbolic solutions cannot be obtained. Two examples are used to illustrate the procedures of how to select the PAR.
In the recent years, the authors have performed a large number of FPS of the PMs [17,18], which proves that the procedures of the selection criteria of PAR for FPS proposed in this paper are universal.
For PMs with branch chains of different topology, the correct selection of the PAR is necessary and important. This work provides new inspiration and the road map for the FPS of these complex PMs.

Author Contributions

Conceptualization, H.S. and T.-l.Y.; methodology, Q.X. and J.L.; validation, Q.X.; writing—original draft preparation, H.S.; writing—review and editing, Q.X. and J.L.; funding acquisition, H.S. All authors have read and agreed to the published version of the manuscript.

Funding

This research is sponsored by the NSFC (No. 51975062, 51375062).

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Kinzel, G.L.; Chang, C. The analysis of planar linkage using a modular approach. Mech. Mach. Theory 1984, 19, 165–172. [Google Scholar] [CrossRef]
  2. Kong, X.; Gosselin, C.M. Generation and forward displacement analysis of RPR-PR-RPR analytic planar parallel manipulators. J. Mech. Des. 2001, 8, 2195–2304. [Google Scholar]
  3. Pennock, G.R.; Hasan, A. A Polynomial Equation for a Coupler Curve of the Double Butterfly Linkage. J. Mech. Des. 2002, 124, 39–46. [Google Scholar] [CrossRef]
  4. Husain, M.; Waldron, K.J. Direct Position Kinematics of the 3-1-1-1 Stewart Platforms. J. Mech. Des. 1994, 116, 1102–1107. [Google Scholar] [CrossRef]
  5. Wampler, C.W. Forward displacement analysis of general six-in-parallel sps (Stewart) platform manipulator using soma coordinates. Mech. Mach. Theory 1996, 31, 311–337. [Google Scholar] [CrossRef]
  6. Husty, M.L. Algorithm for Solving the direct kinematic of Stewart-Gough-Type platforms. Mech. Mach. Theory 1996, 31, 365–380. [Google Scholar] [CrossRef]
  7. Rojas, N.; Thomas, F. On closed-form Solutions to the position analysis of Baranov trusses. Mech. Mach. Theory 2012, 50, 179–196. [Google Scholar] [CrossRef] [Green Version]
  8. Yang, T.; Liu, A.; Shen, H.; Hang, L.; Luo, Y.; Jin, Q. Theory and Appication of of Robot Mechanism Topology; Science Press: Beijing, China, 2012. [Google Scholar]
  9. Yang, T.; Liu, A.; Shen, H.; Hang, L.; Luo, Y.; Jin, Q. Topology Design of Robot Mechanisms; Springer: Singapore, 2018. [Google Scholar]
  10. Shen, H. Research on Forward Position Solutions for 6-SPS Parallel Mechanisms Based on Topology Structure Analysis. Chin. J. Mech. Eng. 2013, 49, 70–80. [Google Scholar] [CrossRef]
  11. Shen, H.; Chablat, D.; Zen, B.; Li, J.; Wu, G.; Yang, T. A Translational Three-Degrees-of-Freedom Parallel Mechanism with Partial Motion Decoupling and Analytic Direct Kinematics. J. Mech. Robot. 2020, 12, 1–7. [Google Scholar] [CrossRef] [Green Version]
  12. Shen, H.; Yang, T.; Li, J.; Zhang, D.; Deng, J.; Liu, A. Evaluation of Topological Properties of Parallel Manipulators Based on the Topological Characteristic Indexes. Robotica 2020, 38, 1381–1399. [Google Scholar] [CrossRef]
  13. Shen, H.; Xu, Q.; Li, J.; Yang, T. The Effect of the Optimal Route Selection on the Forward Position Solutions of Parallel Mechanisms. In Advances in Mechanism and Machine Science; Springer: Cham, Switzerland, 2020; pp. 450–458. [Google Scholar]
  14. Li, J.; Shen, H.; Meng, Q.; Deng, J. A delta-CU—Kinematic analysis and dimension design. In Proceedings of the 10th International Conference on Intelligent Robotics and Applications, Wuhan, China, 16–18 August 2017; Springer: Cham, Switzerland, 2017; pp. 371–382. [Google Scholar]
  15. Shen, H.; Wang, Y.; Wu, G.; Meng, Q. Stiffness Analysis of a Semi-symmetrical Three-Translation Delta-CU Parallel Robot. In Proceedings of the 6th IFToMM International Symposium on Robotics and Mechatronics, ISRM 2019, Taipei, Taiwan, 28 October–3 November 2019. [Google Scholar]
  16. Shen, H.; Xu, Q.; Li, J.; Wu, G.; Yang, T.-L. The Effect of Selection of Virtual Variable on the Direct Kinematics of Parallel Mechanisms. In New Trends in Mechanism and Machine Science; Springer: Cham, Switzerland, 2020. [Google Scholar]
  17. Shen, H.; Ji, H.; Xu, Z.; Yang, T. Design, Kinematic Symbolic Solution and Performance Evaluation of a New Three Translation Mechanism. Trans. Chin. Soc. Agric. Mach. 2020, 51, 397–407. [Google Scholar]
  18. Shen, H.; Zhu, Z.; Meng, Q.; Wu, G.; Deng, J. Kinematics and Stiffness Modeling Analysis of a Spatial 2T1R Parallel Mechanism with Zero Coupling Degree. Trans. Chin. Soc. Agric. Mach. 2020, 51, 411–420. [Google Scholar]
Figure 1. Three-translation parallel mechanisms (PM) (3T-CU). (a) Topology structure; (b) Kinematic modeling of the 3T PM.
Figure 1. Three-translation parallel mechanisms (PM) (3T-CU). (a) Topology structure; (b) Kinematic modeling of the 3T PM.
Robotics 09 00093 g001
Figure 2. Three-translation PM (Delta-CU). (a) Topology structure; (b) Kinematic modeling of the 3T PM.
Figure 2. Three-translation PM (Delta-CU). (a) Topology structure; (b) Kinematic modeling of the 3T PM.
Robotics 09 00093 g002
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Shen, H.; Xu, Q.; Li, J.; Yang, T.-l. The Effect of the Optimization Selection of Position Analysis Route on the Forward Position Solutions of Parallel Mechanisms. Robotics 2020, 9, 93. https://doi.org/10.3390/robotics9040093

AMA Style

Shen H, Xu Q, Li J, Yang T-l. The Effect of the Optimization Selection of Position Analysis Route on the Forward Position Solutions of Parallel Mechanisms. Robotics. 2020; 9(4):93. https://doi.org/10.3390/robotics9040093

Chicago/Turabian Style

Shen, Huiping, Qing Xu, Ju Li, and Ting-li Yang. 2020. "The Effect of the Optimization Selection of Position Analysis Route on the Forward Position Solutions of Parallel Mechanisms" Robotics 9, no. 4: 93. https://doi.org/10.3390/robotics9040093

APA Style

Shen, H., Xu, Q., Li, J., & Yang, T. -l. (2020). The Effect of the Optimization Selection of Position Analysis Route on the Forward Position Solutions of Parallel Mechanisms. Robotics, 9(4), 93. https://doi.org/10.3390/robotics9040093

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop