Abstract
The Lie group Denavit–Hartenberg method and application in the parallel hexapod robot are researched. The hexapod robot and the ground form opened and closed loop alternately; the complete kinematics equation cannot be derived by Denavit–Hartenberg method with a trigonometric function type. The complete kinematics model of the hexapod robot is constructed with the improved Denavit–Hartenberg method. The numerical solving strategy is schemed. The simulation results provide the positive and athwart kinematics response relation during the lift and forward patterns in space. The research shows that the complete kinematics model can be constructed by the Lie group Denavit–Hartenberg method; the numerical calculation method can solve the pose–attitude response correctly.
Keywords
Introduction
Wheel, track, and leg are the three moving modes of the mobile robot. The foot-type robot has a higher terrain adaptive capacity because of the discrete contract with the ground. 1 Compared with the biped and quadruped robot, the parallel hexapod robot has a low gravity center and more supporting points, so it has a higher stability and higher bearing capacity, which has a wide application prospect. It is the best choice in a complex working environment such as the industry, mining, and mountain area. 2
Recently, the exploration about the gait planning, control, and stability analysis of the hexapod robot is proceeding vastly, which is significant to the design and the improvement of the hexapod robot. The parallel hexapod robot consists of many rods which are connected together by the joints. It is a complex closed-loop kinematics system. The gait leads to the variation in the topological relation of the parallel hexapod robot, so the body, leg, and ground form whole parallel mechanism and portion parallel mechanism continuously. The analysis method of the parallel hexapod robot is similar to the method of the parallel mechanism. 3
The basis for the exploration of the parallel hexapod is the establishment of the coordinate connection of the elements which are interconnected. The coordinate relations can be divided into the local coordinates of the leg and the whole coordinate connection includes the ground, body, and the leg. Based on the local coordinates of the leg, many explorations about the design, kinematics, dynamics, and stability of the hexapod robot are completed. Y Zhu et al. 4 completed the optimum structural design of the hexapod robot with the model of the leg. Y Rong et al.5,6 completed the mechanical design, the conformational analysis, and the parameter determination of the leg. Z Deng and Y Liu 7 completed the length proportion exploration of the leg segments. G Chen et al. 8 completed the fixed radius turning gait exploration based on the partial model of the body and the leg. Manoiu-Olaru 9 completed the static stability of the hexapod robot under different displacements and different attitudes of the leg. P Yang and F Gao 10 obtained the forward kinematics model of the hexapod robot, and the load performance is analyzed. M Ghayour and A Zareei11,12 analyzed the forward and inverse kinematics problems of the hexapod robot with the geometry method. L Vladareanu and A Curaj 13 explored the forward and inverse kinematics problem of the leg with 6 degrees of freedom.
Except the local coordinates, the global coordination connection of the whole machine is important for exploration of the hexapod robot. For example, the harmonize gait planning and the stability. Most of the modeling methods are based on the trigonometric function; the complex expression and the calculation process lead to the difficulty for the construction of the whole coordinated relation of the hexapod robot with the complex space motion. So the exploration for a new modeling method which can solve this problem is the key for the construction of the whole coordinate connection of the hexapod robot. Recently, with the development of the computation geometry mechanics, the Lie group theory which is used in the problems of the dynamic analysis, the kinematic analysis of the space rigid body had gained great achievement. The Lie group theory is also used in the optimal control calculation which means that the Lie group modeling method can make the calculation more accurate. T Lee 14 and T Lee et al. 15 combined the Lie group theory and the discrete variational integrator together and obtained the Lie group discrete variational integrator; the method was used in the dynamics exploration of the 3D rigid pendulum. N Nordkvist and AK Sanyal 16 used the Lie group discrete variational integrator to solve the optimal control problem of the underwater vehicle. XL Ding and Y Liu 17 used the Lie group and Lie algebra in the dynamics exploration of the flexibility rod robot.
With the common Denavit–Hartenberg (D–H) method, the kinematics model which can be solved for the complex parallel mechanism cannot be obtained. Practically, the D–H method in space is a type of homogeneous matrix method, which can also be called as the quaternion matrix method; the rotation elements and the displacement elements are mixed operated; and the orthogonal property of the rotation matrix cannot be used. With the triangle functions as the calculation elements, the triangle and the inverse trigonometric transformations certainly exist during the derivation; the singularity of the triangle functions will make the kinematic model not be solved numerically. Even if the pose and attitude relations are obtained, the following velocity and acceleration derivations are difficult to proceed, and the primary cause is also the complexity which is induced by the repeat triangle function transformations. However, the Lie group D–H method uses the orthogonal matrix to express the rotation part in the D–H matrix, and the matrix with the special orthogonal character is called the Lie group. This orthogonal matrix has an exponent mapping relation with the rotation angles. So the original quaternion matrix using the orthogonal matrix and the vectors as the elements and the modeling process can be simplified vastly.
In this article, the space pose and attitude representation method of the single rigid body is explored first, then the D–H method is improved by the Lie group theory, and finally, the method is used in the kinematics modeling of the whole parallel hexapod robot. The numerical calculation method is built, and the calculation results are compared with the simulation results by ADAMS, and the correctness of the model is testified. This exploration offers a common mathematical model and a common numerical solving method for the design and gait planning of the parallel hexapod robot.
Lie group D–H method
First, the space rigid body pose and attitude expression method with the Lie group type are introduced, and then the Lie group D–H method which is used to express the space orthogonal motion of the joints is brought out. The pose and attitude of the free rigid body can be expressed as the four-dimensional matrix as given in equation (1)
In equation (1),
The single-degree-of-freedom rotation of the robot leg’s joints can be seen as a reduced form of the three-dimensional (3D) space rotation of the above-mentioned rigid body, so the D–H method based on the traditional triangle function can be transformed to be a Lie group type. The traditional D–H method is based on the scalar, and every rotation motion and the displacement motion are accomplished along one axis. This conducted alternatively for the rotation and displacement lead to the complexity of the solution. To solve this problem, the D–H method is improved; all the displacements along the three axes boil down to one transformation, and then the rotation transform proceeds. The transform matrixes of the displacement and the rotation are given in equation (2)
In equation (2),
The pose and attitude connection of the whole body under the inertial coordinate
The 3D model of the whole body of the hexapod robot is shown in Figure 1. The hexapod robot can be divided into two types of parts on the structure, the body and the leg. The leg can be divided into the hip, the shank, and the thigh. The connection between the ground and the foot tip of the shank can be expressed as

The pose and attitude relation of the whole body of the hexapod robot.

The coordinate distribution of the different joints on the leg of the hexapod robot.
The open-loop pose and attitude relation of the whole machine
The trunk of the hexapod robot has three types of possible motions as pitching, rolling, and yawing, which rotate along the principle axis of the trunk. The kinematics model of the trunk with 6 degrees of freedom should be built up first. According to Figure 1, the trunk can be seen as a free rigid body with 6 degrees of freedom without consideration of the leg. Based on formula (1), the pose and attitude relation of the body frame relative to the inertial frame can be expressed as formula (4)
In formula (4),
So the pose and attitude of the hip rotation center
After the calculation, the rotation matrix and the displacement of the rotation center in space can be derived as formula (7)
Point
There is no rotation from
Supposing the position vector of
Then the pose and attitude matrix of the frame relative to the inertial frame is given as formula (11)
The rotation matrix and displacement vector of the push rod of the hip in the inertial frame is given as formula (12), with formula (11) to be expanded
Suppose that the position vector of
The pose and attitude matrix of the push rod
Then the position vector of
According to the sequence of the displacement as
The pose and attitude matrix of the point in the space is given as formula (17)
The rotation attitude and displacement vector of the push rod of the thigh rotate along the point of
Suppose that the position vector of point
Then the pose and attitude matrix of the inertial frame is given as formula (20)
The position vector of point
The conversion process from
The pose and attitude matrix of the frame in the inertial frame is given as formula (23)
The rotation matrix and displacement vector of the thigh rotate along the point of
The transformation process from frame
Then the pose and attitude matrix of the frame
The rotation matrix of the shank rotates along
Displacing
The pose and attitude transformation matrix of point
The displacement vector of point
Displacing
The pose and attitude transformation matrix of
The rotation matrix and the position vector of
The pose and attitude transformation matrix of
The position vector of
Suppose that the pose and attitude transformation matrix of
Then the pose and attitude transformation matrix of
Then the position vector of
The pose and attitude matrix of
Then the position vector of
The pose and attitude constraints
Each component of the hexapod robot is drove by the push rod, so the connection between the length of the push rod and the rotation angle of the joint should be built, and the connection between the length of the push rod and the rotation angle of the push rod should also need to be built up. First, the constraint of the push rod of the hip can be built up by the length of the push rod and the coordinate value of the points according to formulas (10) and (13). The result is given as formula (41)
Expanding formula (41), the concrete expression of formula (41) is obtained as formula (42)
From formula (43), the rotation matrix of the push rod can be derived by the known length of the push rod of the hip and the rotation matrix of the hip. Similarly, the constraint of the thigh can also be derived. According to the equivalence relation between formulas (22) and (31), formula (45) can be derived which expresses the rotation matrix of the push rod of the thigh
According to formulas (19) and (31), the constraint of the drive of the thigh joint is expressed as formula (45)
The concrete expression of formula (45) is given as formula (46)
The push rod of the shank satisfies the following constraint as formula (48)
The concrete expression of formula (48) is expressed as formula (49)
For the advance movement of the hexapod robot realized by the alternate contact between the foot tip and the ground, the foot tip has two conditions. The first is the free-state, which means that the foot tip can move in the space according to the drive of the push rod of the joints. The other is the fixed state, which means that when the foot tip contacts with the ground and plays a supporting role, the displacement of the foot tip in space keeps still, which is expressed as formula (50)
The numerical solution strategy of the pose and attitude relation in space
The wholly pose and attitude solution of the hexapod robot in space has three types. The first one is the open-loop solution of the mechanism, which is used to decide the pose and attitude range of the points on the mechanism. It provides the reference parameters for the structure design. The second is the forward solution, which means solving the rotation angle of the joints under the condition that the pose and attitude of the trunk are known. The forward solution is used to offer references for the gait planning of the hexapod robot. The third is the inverse solution, which means solving the pose and attitude of the body under the condition that the rotation angles of the joints are known. For the complexity of the mechanism of the hexapod robot, the reference function of the inverse solution is lower, which is often used as the verification for the correctness of the forward solution results.
Based on formula (41), the open-loop solution of the displacement
Supposing that the rotation angles of the body along the x-, y-, and z-axes of the inertial coordinate are
To decide the rotation matrix of the joints, the triangle function expressions of the rotation matrix of the joints are needed. The rotation matrix of the rigid body rotating along the z- and x-axes is given as formula (52)
Supposing that the rotation matrixes of
When the foot tip and the ground keep still, the trunk of the robot can move and rotate in space, which is under the support of the leg; the trunk and the leg consist a closed-loop mechanism. When there is no redundancy of the freedom, the pose and attitude of the trunk and the rotation angles of the joints of the legs have a one-to-one correspondence connection. After the transposition work of the pose and attitude of the trunk in the model of the whole machine pose and attitude model, the parameters of the trunk and the joints of the legs are at different sides of the equation
From formula (54), the pose and attitude of the trunk and the attitude of the leg constitute a nonlinear equation system, which is a 3D system. When the pose and attitude of the trunk are known, the left side of the equation system has no variables, and the right side of the equation has three unknown quantities, so the equation system has full rank and can be solved.
When the rotation angles of the leg are known, the right side of the equation system is constant, and the left side of the equation system has six unknown quantities. To solve the pose and attitude of the trunk, the rotation angles of the two legs should be known, and the equation system can be solved only if the system has a dimension of six.
For the high stability of the hexapod robot, in the practice engineering usage, except the instability condition where the trunk has 6-degree-of-freedom motion in space, the trunk often has 2 degrees of freedoms during the conditions of straight line walking and turning motion. During straight line walking, the trunk does not rotate; the only motion is the displacement motion on the plane surface along the two directions. The attitude matrix of the trunk can be simplified as
From formula (55), when the hexapod robot moves along the x-direction with the triangle gait, it can be realized by the synergic movement of the three joints of the leg; the motion of the joints of the shank and the thigh is used to compensate the cross range shrink which is caused by the triangle gait of the hip.
During turning motion, the most ideal condition is that the trunk rotates only along one axis, so the trunk has only 1 freedom too. At this condition, the attitude matrix only needs one angle to describe. So equation (54) can be simplified as formula (56)
Equations (54)–(56) are the pose and attitude equations of the parallel hexapod robot under the three conditions, which are the general state, the straight line state, and the turning state. The straight line state and the turning state are the simplified formal of the general state, so the three equation systems have the same numerical solving strategy. The numerical solving strategy is listed in Table 1.
The numerical solving strategy of the pose and attitude response of the hexapod robot.
Simulation result
To testify the correctness of the above derivation, the complete machine model of the parallel hexapod robot is built up by the 3D model software. According to the measurement in it, the structure parameters of each part of the hexapod robot are as follows. The common structure parameters of each leg are as follows:
The nonlinear equations of the six legs have the same part as
The pose–attitude variation in the joints on the leg under straight line walking and turning motion is analyzed. During straight line walking, the trunk only has the forward direction displacement which means the displacements along the y- and z-axes are 0, as
The left side of the equation is formula (57), and the right side of the equation is as follows for each leg
According to the about analysis, the legs numbered as 1 3 5 have the same kinematic equation, so as the legs which numbered as 2 4 6 during straight line walking. The kinematic equation of the hexapod robot under turning motion is analyzed as follows. Supposing that the hexapod robot rotates along the fixed axis which is at the mass center, and
The left side of formula (59) is identical to the left side of formula (57), and the right side can be written as follows which represents the six legs
First, the motions of the six legs under straight line walking are calculated. Supposing that the trunk of the hexapod robot moves with a constant speed and the velocity is 5 mm/s, the motion time is 20 s, so the displacement of the trunk is 10 cm. The simulation results of the motion of the hips, thighs, and shanks of the six legs and their drive cylinders are given in Figure 3.

The kinematic results of the hip thigh and the shank under straight line walking.
The first column of Figure 3 is the motion curves of the parts of the hip, the rotation angle of the hip
The second column of Figure 3 is the motion curves of the main parts of the thigh; the third column is the curves of the shank. The main kinematics parameters of the thigh are the rotation angles of the thigh
The main kinematics parameters of the shank are the rotation angle of the shank
The list of the initial terminal and the amplitude values of the motion of each joints under straight line walking.
According to the overall variation tendency of the above curves, the kinematic variation in the parts of the hips tends approximately to be straight line type, and the variation in the thigh and the shank tends to be parabolic.
Figure 4 shows the comparison of the motion amplitudes of each joint under straight line walking. The first group is the comparison of the rotation angles of the joints of hip thigh and shank. The second group is the comparison of the length of the drive cylinders. The third group is the rotation angles of the drive cylinders. According to the three groups’ comparison, the conclusion can be made that the hip and the shank joints are the main motion joints during straight line walking; the thigh has only a small motion amplitude. So in practical engineering, the thigh joint can keep still during straight line walking to reduce the difficulty of the control.

The comparison of the motion amplitudes of each joint under straight line walking.
The motions of the six legs under turning motion are simulated. Supposing that the trunk of the hexapod robot rotates 10° in 2 s along the z-axis of the body frame of the trunk, the simulation results of the components of the legs are given in Figures 5 and 6. The initial and terminal values and the variation amplitudes of each kinematics parameters are listed in Table 3.

The kinematic results of the hip thigh and the shank under turning motion of leg 1 3 5.

The kinematic results of the hip thigh and the shank under turning motion of leg 2 4 6.
The list of the initial terminal and the amplitude values of the motion of each joints under turning motion.
According to the simulation results in Figures 5 and 6, during turning motion, the motion curves of the joints of the robot appear straight line and parabolic type approximately, and there is no fluctuant. According to the results in Table 3, during the setting turning process, the rotation angles of the hips of the six legs are 15.43°, 12°, 13.06°, 13.8°, 12.09°, and 15.4°, respectively; the motion lengths of the drive cylinders of the hips are 23.7, 18.9, 20.2, 21.6, 18.7, and 24 mm, respectively; and the rotation angles of the drive cylinders of the hips are 0.95°, 0.47°, 0.7°, 1°, 0.61°, and 1.26°, respectively. The rotation angles of the thigh are 0.4894°, 4.4°, 0.9836°, 0.4644°, 5.032°, and 0.3642°; the motion lengths of the drive cylinders of the thighs are 0.2, 1.3, 0.3, 0.2, 1.4, and 0.2 mm; and the rotation angles of the drive cylinders of the thighs are as 0.2°, 1.87°, 0.42°, 0.19°, 2.14°, and 0.15°. The rotation angles of the shanks are 12.8°, 18.32°, 5.49°, 3.93°, 20.28°, and 13.8°; the motion lengths of the drive cylinders of the shanks are 15.4, 19, 6.1, 4.6, 20.8, and 16.8 mm; and the rotation angles of the drive cylinders of the shanks are 0.39°, 4.62°, 1.3°, 0.87°, 5.16°, and 2.8°. With the above analysis, the comparison of the motion amplitudes of the rotation angles, the motion lengths of the drive cylinders, and the rotation angles of the drive cylinders is given in Figure 7. According to Figure 7, during turning motion, the hips and the shanks of the legs have a significant function, and the motion amplitudes of the joints of the thighs are small comparatively.

The comparison of the motion amplitudes of each joint under turning motion.
According to the simulation results of straight line walking and turning motion, the hips and the shanks play the main function, and the motion amplitude of the thighs is small, which can be used as the standby joints in the obstacle crossing.
The virtual prototype
To testify the correctness of the kinematic model, the virtual prototype of the hexapod robot is built by the 3D modeling software Pro-E and the virtual prototype software ADAMS. The virtual prototype is given in Figure 8.

The virtual prototype of the hexapod robot.
There are 54 revolute pairs and 18 sliding pairs. The tips of the feet are connected together by the spherical pair which can constitute the closed loop between the hexapod robot and the ground. The legs are numbered 1–6 which are in accordance with the leg order in the above simulation. The simulation results of the motion of each joint under straight line walking and turning motion are given in Figures 9 and 10, respectively.

The rotation angles and displacements of the joints of the six legs under straight line walking.

The rotation angles and displacements of the joints of the six legs under turning motion.
In Figures 9 and 10, the first, second and the third columns are the kinematic parameters of the hips, the thighs, and the shanks, respectively. The parameters include the rotation angles of hips, thighs, and shanks; the displacements of the sliding pairs in the drive cylinders; and the rotation angles of the drive cylinders.
The comparisons of the variation amplitudes of the kinematic parameters under straight line walking and turning motion which are calculated by MATLAB and ADAMS are listed in Tables 4 and 5, respectively. According to Tables 4 and 5, the calculation results which are calculated by MATLAB and ADAMS are identically approximately, which verifies the correctness of the mathematical model which are derived above. The time step is 0.1 s in the MATLAB simulation, so the accuracy of the parameters which is calculated by MATLAB is lower than ADAMS.
The comparison of the kinematics parameters under straight line walking with MATLAB and ADAMS.
The comparison of the kinematics parameters of each joint under turning motion with MATLAB and ADAMS.
Conclusion
This article explores the advantage and defects of the D–H mechanism modeling method and the Lie group multi-body modeling method, and then combines them together to get the Lie D–H method. The closed-loop pose–attitude equation of the hexapod robot from the body to the foot tip is constructed by the Lie D–H method, with the attitude matrixes and the pose vectors of the legs as the modeling elements, the pose-attitude model has a more concise expression type, and the skew character of the attitude matrix is sufficiently used, so a mass of the intermediate variables is eliminated, which avoids the complexity of the calculation. The numerical calculation method is designed; straight line walking and turning motion of the hexapod robot are simulated with MATLAB; and the rotation and displacement response of each joint and their drive cylinders of the legs are obtained. Finally, the 3D model of the pneumatic hexapod robot is constructed with Pro-E, and the virtual prototype analysis is realized by ADAMS. The correctness of the mathematical model is verified by the comparison between the simulation results by MATLAB and ADAMS. This mathematical model offers a theory analysis basis for the mechanism design and gaiting planning of the pneumatic- or hydraulic-derived hexapod robot.
Footnotes
Academic Editor: Yangmin Li
Declaration of conflicting interests
The author(s) declared no potential conflicts of interest with respect to the research, authorship, and/or publication of this article.
Funding
The author(s) disclosed receipt of the following financial support for the research, authorship, and/or publication of this article: The exploration is supported by the Natural Science Foundation of China (11472058).
