Next Article in Journal
Reliability and Inter-Device Agreement Between a Portable Handheld Ultrasound Scanner and a Conventional Ultrasound System for Assessing the Thickness of the Rectus Femoris and Vastus Intermedius
Previous Article in Journal
Annual Performance Progression in Swimming Across Competition Levels and Race Distances
Previous Article in Special Issue
Continental Assessment of Work-Related Musculoskeletal Disorders Prevalence Among Surgeons: Systematic Review and Meta-Analysis
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Dual Quaternion-Based Forward and Inverse Kinematics for Two-Dimensional Gait Analysis

by
Rodolfo Vergara-Hernandez
,
Juan-Carlos Gonzalez-Islas
*,
Omar-Arturo Dominguez-Ramirez
,
Esteban Rueda-Soriano
and
Ricardo Serrano-Chavez
Basic Sciences and Engineering Institute, Autonomous University of the State of Hidalgo, Pachuca 42184, Hidalgo, Mexico
*
Author to whom correspondence should be addressed.
J. Funct. Morphol. Kinesiol. 2025, 10(3), 298; https://doi.org/10.3390/jfmk10030298 (registering DOI)
Submission received: 21 June 2025 / Revised: 22 July 2025 / Accepted: 27 July 2025 / Published: 1 August 2025

Abstract

Background: Gait kinematics address the analysis of joint angles and segment movements during walking. Although there is work in the literature to solve the problems of forward (FK) and inverse kinematics (IK), there are still problems related to the accuracy of the estimation of Cartesian and joint variables, singularities, and modeling complexity on gait analysis approaches. Objective: In this work, we propose a framework for two-dimensional gait analysis addressing the singularities in the estimation of the joint variables using quaternion-based kinematic modeling. Methods: To solve the forward and inverse kinematics problems we use the dual quaternions’ composition and Damped Least Square (DLS) Jacobian method, respectively. We assess the performance of the proposed methods with three gait patterns including normal, toe-walking, and heel-walking using the RMSE value in both Cartesian and joint spaces. Results: The main results demonstrate that the forward and inverse kinematics methods are capable of calculating the posture and the joint angles of the three-DoF kinematic chain representing a lower limb. Conclusions: This framework could be extended for modeling the full or partial human body as a kinematic chain with more degrees of freedom and multiple end-effectors. Finally, these methods are useful for both diagnostic disease and performance evaluation in clinical gait analysis environments.

1. Introduction

The study of human gait is an interdisciplinary field that integrates principles of biomechanics, neurophysiology, and orthopedics to understand movement patterns during bipedal locomotion [1]. The use of technologies such as force platforms and wearable or marker-based and marker-less systems for gait analysis allows the quantification of spatiotemporal, kinematic, and kinetic parameters, essential for the evaluation of neuromuscular pathologies, musculoskeletal injuries, and therapeutic interventions [2]. Recent advances in machine learning algorithms and wearable and inertial sensors have improved the accuracy and accessibility of these analyses, facilitating their application in clinical and sports environments [3].
Kinematics is the branch of mechanics that deals with the geometry of motion of rigid bodies without considering the masses of those bodies or the forces that cause movement. Forward and inverse kinematics are fundamental problems in clinical and research biomechanics [4]. The forward kinematics (FK) problem involves determining the position and orientation of the end-effector of an articulated chain given a collection of known joint angles and segment lengths, while the inverse kinematics (IK) problem seeks to calculate the joint angles using the known position and orientation of the end-effector and segment lengths [5]. Differential kinematics concerns the relationship between velocities. The forward differential kinematics problem consists in the determination of linear and angular velocities of the end-effector from known joint velocities. The inverse differential kinematic problem looks for the opposite relationship. Differential kinematics is often used to solve the IK problem through the derivation of the Jacobian matrix. Kinematic gait analysis involves the analysis of joint angles and segment movements during walking; previous studies suggest that examination of kinematic differences during the gait cycle can provide information related to the function of the lower limb to recommend postural control strategies [6]. Kinematic analysis and gait characterization have been used in many fields, including path planing for biped walking robots and humanoids [7,8], development of robotic exoskeletons for gait assistance [9], age-based performance evaluation [10], chronic stroke assessment [11], or cerebral palsy rehabilitation [12].
The solution to the FK problem has been extensively documented in the literature. A detailed description of the method for solving this problem using homogeneous transformation matrices is provided in [13]. Although rotation matrices in 3D space have nine elements, only three of them are independent, corresponding to the three degrees of freedom (DoF). This redundancy may lead to computational inefficiency [14]. Other ways of representing rotations are described in [15], such as the Euler angles representation, which uses three independent parameters, or the axis–angle representation, which uses four parameters to express the rotation of a given angle with respect to an axis in 3D space. Although these representations reduce parameter redundancy, they must be converted into rotation matrices to perform forward kinematics calculations.
Many robotics tasks, such as object manipulation, path tracking, or viewpoint control, rely on inverse kinematics (IK). However, for open kinematic chains, such as the human lower limb model used in this work, the IK problem is often difficult to solve analytically, and when closed forms solutions can be found, they are seldom unique [16]. On the other hand, numerical algorithms such as Newton–Raphson, Jacobian methods, and damped least squares converge to a single solution for IK [17]. Metaheuristics have recently attracted a lot of attention in the pursuit of answers to challenging optimization issues in subjects such as inverse kinematics [18]. Artificial intelligence has already been used in combination with dual quaternions to analyze and eliminate accumulated errors in the FK and IK of a robot arm. This combination showed high efficiency and accuracy and has the important advantage of being able to obtain the robot arm parameters without knowing the robot’s structure in advance [19].
Recently, quaternions have emerged as a fundamental tool in the kinematic analysis of robots and biomechanical systems with complex chains and structures due to their computational efficiency and absence of singularities, overcoming limitations of representations based on Euler angles [20]. Quaternions have also been used efficiently for the kinematics and dynamics of rigid bodies [21,22]. Using the dual-quaternion exponential and logarithm, an efficient derivation of dual-quaternion forms of forward, differential, and inverse kinematics that eliminates the singularity is possible [23]. This approach offers a potential way to use planar quaternions to control the 3-DoF of planar parallel mechanisms based on forward kinematics in real time [24]. The most related work presents a method to solve the inverse kinematic problem for articulated chains using an iterative dual-quaternion and exponential mapping strategy [25]. However, the authors point out some important limitations: when the joints are very close to their angular limits, the computed angles are pushed back and forth repeatedly, increasing the time to converge to a solution. Also, because the joint angles have not been weighted or coupled, some solutions generate unnatural postures. In addition, there are still problems to be solved, such as the compensation of modeling errors in biomechanical systems using quaternions, the real-time implementation in embedded platforms, or the generalization of quaternion-based methods for soft robots with nonlinear deformations.
In addition to the above-mentioned problems related to quaternion-based kinematic modeling, very few studies, including our previous works, have focused on the use of this approach to model human gait [26,27]. In [28] an approach for data based prediction of rigid body movements is presented. The method uses a combination of data-based learning with a physically motivated neural network architecture and dual quaternions. The obtained results support the applicability and potential of the approach in terms of improving prediction performance.
Therefore, this study proposes a framework for the solution of forward and inverse kinematics problems applied to gait analysis in the sagittal plane of a 3-DoF kinematic model of the lower limb. This is guided by our overarching research question: How to model the kinematics of a lower limb during the gait cycle using dual quaternions for gait analysis in the sagittal plane? The main contribution of this work is the proposed framework to model and evaluate the motion of a lower limb during the gait cycle using dual quaternions, which can be extended to a kinematic chain with more DoF and multiple end-effectors.

2. Materials and Methods

Figure 1 depicts the general framework for the 3-DoF human gait analysis used in this work. The framework consists of a sequence of processes to solve the forward and inverse kinematics problems for a kinematic chain representing a human lower limb. The first forward kinematic process ( FK 1 ) has two inputs: the body segments parameters and the reference joint angles.
The input joint angles of the 3-DoF kinematic model consist of hip flexion–extension, knee flexion–extension, and ankle dorsiflexion–plantarflexion. With the objective to assess the accuracy of the IK method in different scenarios, we use three different gait cycles: normal gait, toe-walking, and heel-walking. The dataset of reference joint angles, publicly available and recorded using the SMART-E motion capture system (BTS, Milano, Italy), was acquired at 60 Hz during gait cycles performed by a group of subjects aged 22 to 72 years (mean 43.1 ± 15.4 ), with a mean body mass of 68.5 ± 15.8 kg and a mean height of 1.71 ± 0.10 m [29].
The anatomical model used in this work corresponds to a subject with a height of 1.65 m. It is considered representative of the population of the dataset, since its height lies within one standard deviation from the mean height of the dataset population. The femur and tibia lengths, as well as lateral malleolus height and the distance from the lateral malleolus to the distal phalanx of the hallux (LM-to-DPH) were defined based on the adult human male anthropometric proportions [30] and measurements [31]. The body segments parameters are summarized in Table 1.
The FK 1 solution is a set of coordinates that describe the positions of anatomical landmarks in the knee, ankle, and toe in the sagittal plane, as well as the orientations of the femur, tibia, and foot with respect to the global coordinate system (referred to as workspace coordinates 1). Next, using the workspace coordinates 1, an IK method is used to estimate a set of joint angles (designated as estimated joint angles) that best reproduce the corresponding positions and orientations of anatomical landmarks and body segments. The second forward kinematics process ( FK 2 ) is then applied to the estimated joint angles to compute a second set of workspace coordinates (identified as workspace coordinates 2) for comparison purposes. To validate the results, RMS errors were calculated between the reference and estimated joint angles, as well as between workspace coordinates 1 and 2. Furthermore, all coordinates of the workspace and joint space were visualized and compared using 2D plots and a 3D model of the human right lower limb. A detailed description of each process, along with the fundamental theory, is provided in the following sections.

2.1. Quaternions Preliminaries

Quaternions were described by William Rowan Hamilton in 1843 [32]. Let H denote the set of quaternions. A quaternion q H is defined as
q = q 0 + q 1 i + q 2 j + q 3 k = q 0 + q ,
where q 0 , q 1 , q 2 , q 3 R . The term q 0 is the real or scalar part and q = q 1 i + q 2 j + q 3 k R 3 is the imaginary or vector part. The elements { i , j , k } are the unit vectors or imaginary units that satisfy i 2 = j 2 = k 2 = i j k = 1 and form the orthonormal basis for R 3 [33]. Quaternions can also be represented as a column vector in R 4 , that is
q = [ q 0 , q 1 , q 2 , q 3 ] T .
The following is a brief introduction to the essential definitions on quaternion and dual-quaternion algebra. For a comprehensive description of quaternion algebra refer to [34].
Given p , q H the following quaternion operations are defined:
  • Addition. p + q = ( p 0 + p ) + ( q 0 + q ) = ( p 0 + q 0 ) + ( p 1 + q 1 ) i + ( p 2 + q 2 ) j + ( p 3 + q 3 ) k .
  • Multiplication. ( p 0 + p ) ( q 0 + q ) = p 0 q 0 p · q + p × q + p 0 q + q 0 p , where · and × denote the scalar and vector product in R 3 , respectively [35]. Multiplication is associative and distributive but non-commutative.
  • Multiplication identity. 1 = 1 + 0 .
  • Conjugate. q * = q 0 q 1 i q 2 j q 3 k = q 0 q .
  • Magnitude. | q | = q q * = q 0 2 + q 1 2 + q 2 2 + q 3 2 R .
  • Inverse. q 1 = q * | q | 2 , such that q q 1 = q 1 q = 1 .
There are two important subsets of H :
  • H 1 H is the set of unit quaternions defined as
    H 1 { q H : | q | = 1 } .
    This subset forms the 3-sphere S 3 R 4 and is used to represent 3D rotations. The inverse of a unit quaternion is its conjugate.
  • H p H is the set of pure quaternions defined as
    H p { q H : q 0 = 0 } .
    Since the vector part of q H p is a column vector q R 3 , pure quaternions are commonly used to represent vectors and translations in 3D.

2.2. Rotations Using Unit Quaternions

Unit quaternions can be treated as rotation operators in R 3 . Figure 2 shows the projection of a unit quaternion in the complex plane, where it can be visualized as the radius of a unit circle. Let q H 1 , and given that | q | = 1 , then
q 0 2 + | q | 2 = 1 .
Moreover, since for every angle θ , it is satisfied that cos 2 θ + sin 2 θ = 1 , there exists an angle θ ( π , π ] such that cos θ = q 0 and sin θ = | q | [34]. Also, a unit vector u = q | q | = q sin θ representing the rotation axis of q can be defined. Then, q can be written in terms of the angle θ and the unit vector u as
q = q 0 + q = cos θ + u sin θ .
The product of two unit quaternions that have the same rotation axis u is a unit quaternion that represents the sum of the two rotation angles about u . Let p = cos α + u sin α H 1 and q = cos β + u sin β H 1 , the quaternion product p q results in the following:
p q = cos ( α + β ) + u sin ( α + β ) H 1 .
A unit quaternion q H 1 can be used to rotate a vector in R 3 by applying the transformation q v q * , where v H p is a pure quaternion that represents a 3D vector in the quaternion space. As an example, consider the unit quaternion q = cos θ + k sin θ representing a rotation of angle θ about the unit vector k . Applying this rotation to the basis vector i gives the following:
q i q * = ( cos θ + k sin θ ) ( 0 + i ) ( cos θ k sin θ ) = i cos 2 θ + j sin 2 θ H p .
Using the right-hand rule for rotation, the result is the vector i rotated counter-clockwise through an angle 2 θ , about the vector k as an axis. Due to the fact that quaternion multiplication is non-commutative, the operation
q * i q = i cos 2 θ j sin 2 θ H p ,
results in the vector i rotated clockwise through an angle 2 θ , about the vector k as an axis.
Extending Euler’s equation for the exponential map of a complex number to quaternions, a unit quaternion can be defined as the exponential map of an angle and a unit vector pair ( θ , u ) . Let Φ = Φ 0 + Φ = 0 + 1 2 θ u H p , where, given the results of Equations (8) and (9), half the angle θ is used. The quaternion associated with this rotation is given by
q = e Φ 0 + Φ = e Φ 0 e Φ = cos ( | Φ | ) + sin ( | Φ | ) | Φ | Φ
where u = Φ | Φ | and θ 2 = | Φ | [36]. However, when | Φ | = 0 , there is a singularity in sin ( | Φ | ) | Φ | [23]. In order to avoid it, a Taylor series is used:
sin ( | Φ | ) | Φ | 1 | Φ | 2 6 + | Φ | 4 120
On the other hand, the logarithm of a unit quaternion q H 1 that encodes a rotation of an angle θ 2 about an axis u is given by
θ = 2 · arctan 2 ( | q | , q 0 ) ,
Φ = 1 2 ln ( q ) = 1 2 ln ( | q | ) + θ | q | q = 0 + 1 2 θ u H p .
Note that, although the rotation angle θ could be recovered using θ = 2 · arccos q 0 , this formulation restricts the rotation to the interval 0 θ < π . In contrast, using θ = 2 · arctan 2 ( | q | , q 0 ) the possible rotation angles are in the range π < θ π , ensuring proper treatment of positive and negative rotations. When | q | = 0 , the expression θ | q | is not defined, and this is handled using a Taylor series as follows:
θ | q | = θ sin θ | q | 1 + θ 2 6 + 7 θ 4 360 | q |

2.3. Dual Quaternions

Dual quaternions combine ordinary quaternions and dual numbers [23]. A dual quaternion is a number of the form
q ̲ = q p + ε q d H
where q p H is the primary part, q d H is the dual part, and ε is the dual operator satisfying ε 2 = 0 . Given p ̲ , q ̲ H , the following dual quaternion operations are defined:
  • Multiplication. p ̲ q ̲ = p p q p + ε p p q d + ε p d q p + ε 2 p d q d = p p q p + ε ( p p q d + p d q p ) .
  • Conjugate. q ̲ * = q p * + ε q d * .
  • Norm. | q ̲ | = q ̲ q ̲ * = | q p | + ε q p · q d | q p | .
  • Inverse. q ̲ 1 = q ̲ * | q ̲ | 2 = q p 1 ε q p 1 q d q p 1 . Only when q p 0 .
A dual quaternion is a unit if and only if | q p | = 1 and q p · q d = 0 . The set of unit dual quaternions is denoted as H 1 { q ̲ H : | q ̲ | = 1 } [33]. Unit dual quaternions are always invertible because their inverse is their conjugate.

2.4. Rigid Transformations Using Dual Quaternions

Geometrically, elements of H 1 equipped with the multiplication operation represent rigid motions in Euclidian 3D space [33]. Let r = e 1 2 u θ H 1 and p = 0 + p H p ; the translation p followed by the rotation r is given by
q ̲ = ( 1 + ε 1 2 p ) r = r + ε 1 2 p r H 1 .
Conversely, for any q ̲ = q p + ε q d H 1 the rotation is given by r = q p H 1 , and the translation is given by
p = 2 q d ( q p ) * = p r r * H p .
Remarkably, the composition of rigid transformations is given by a sequence of unit dual quaternion multiplications. Let q ̲ 1 , q ̲ 2 H 1 , thus
q ̲ 3 = q ̲ 1 q ̲ 2 = r 1 + ε 1 2 p 1 r 1 r 2 + ε 1 2 p 2 r 2 = r 1 r 2 + ε 1 2 ( r 1 p 2 r 2 + p 1 r 1 r 2 ) .
Note that the primary part of the result is the composition of the rotations as shown in Equation (7); that is
q 3 p = r 1 r 2 H 1 ,
whereas the composition of translations can be obtained from the dual part using Equation (17) as follows
p 3 = 2 q 3 d q 3 p * = ( r 1 p 2 r 2 + p 1 r 1 r 2 ) r 2 * r 1 * = p 1 + r 1 p 2 r 1 * H p .

2.5. Three-DoF Kinematic Model of the Human Lower Limb

The biomechanical functions of the human body can be represented using a series of rigid bodies connected by joints. Figure 3 shows the collection of 3 rigid bodies connected by 3 revolute joints used to analyze the motion of the right lower limb in the sagittal plane. A revolute joint allows rotation around a single axis; therefore, each joint has one degree of freedom (DoF), while the resulting kinematic chain has three DoF.
The global coordinate system is represented by the fixed frame F 0 with coordinate axes x 0 , y 0 and z 0 pointing in the anterior, cranial, and lateral (to the right) directions, respectively. The origin of F 0 is the origin of the kinematic chain and is also referred to as the frame of joint 0. The hip, knee, and ankle joints correspond to indices i = { 1 , 2 , 3 } , respectively. These joints are associated with the femur, tibia, and foot segments, in that same order. Each joint is assigned a local coordinate frame, denoted by F i , which defines the position of the anatomical landmarks at the joints and the orientation of the corresponding body segments. In anatomical posture all frames F i are aligned with frame F 0 , this is the initial posture of the kinematic chain. Global coordinates, expressed with respect to F 0 , are denoted by the superscript W, whereas relative coordinates, expressed with respect to the local coordinate frame of the preceding joint, are denoted by the superscript R.
Figure 3a illustrates that the distance from the origin of the global coordinate frame F 0 to the hip joint frame F 1 is expressed by p 1 R = 0 , since they are at the same point in space. The lengths of the femur and tibia are indicated by the y component of p i R R 3 for i = { 2 , 3 } , respectively, and correspond to the values listed in Table 1.
The symbol Φ i = 1 2 θ i u i in Figure 3b denotes the axis–angle pair at each joint (also known as the joint configuration), where θ 1 is the hip flexion–extension angle, θ 2 is the knee flexion–extension angle, and θ 3 is the ankle dorsiflexion–plantarflexion angle. The rotation axis of each joint is given by u i = [ 0 , 0 , 1 ] . For the 3-DoF kinematic chain representing the lower limb, the chain configuration is given by
Φ = { Φ 1 , Φ 2 , Φ 3 } .
The anatomical landmark at the toe is considered the end-effector of the kinematic chain and is assigned the local coordinate frame F g . The distance from F 3 to F g is represented by the x and y components of p g R R 3 and take the values given in Table 1. The relative orientation between F g and F 3 is indicated by the rotation vector Φ g = 0 , since the orientation of the end-effector follows that of the ankle joint (joint 3).

2.6. Forward Kinematics

The posture (position and orientation) of any coordinate frame F in the global coordinate system is defined as
ξ = p W , o W R 6 ,
where p W R 3 and o W R 3 are the position and orientation vectors in F 0 , respectively. Specifically, the positions are given by the 3D vectors p g W = [ p g , x W , p g , y W , p g , z W ] for the end-effector and p i W = [ p i , x W , p i , y W , p i , z W ] for the anatomical landmarks at the joints. The orientations are given by the 3D vector o g W = [ o g , x W , o g , y W , o g , z W ] for the foot and o i W = [ o i , x W , o i , y W , o i , z W ] for the femur ( i = 1 ) and the tibia ( i = 2 ). The forward kinematics problem is described formally by
ξ = f ( Φ ) .
where f is a non-linear function that uniquely determines the posture of a given anatomical landmark F , based on the chain configuration vector Φ up to that point.
Let r i R ( Φ i ) = e Φ i H 1 and p i R = 0 + p i R H p be rotation and translation quaternions, respectively. The unit dual quaternion that represents the position and orientation of the local coordinate frame F i with respect to the local coordinate frame F i 1 is given by
q ̲ i R ( Φ i ) = 1 + ε 1 2 p i R r i R ( Φ i ) H 1 .
The unit dual quaternion that represents the posture of the end-effector coordinate frame F g relative to the global coordinate frame F 0 can be found by
q ̲ g W ( Φ i ) = q ̲ 3 W ( Φ ) q ̲ g R ( Φ g ) = q ̲ 0 W q ̲ 1 R ( Φ 1 ) q ̲ 2 R ( Φ 2 ) q ̲ 3 R ( Φ 3 ) q ̲ g R ( Φ g ) ,
where
  • q ̲ 0 W = 1 + 0 H 1 indicates that joint 0 is fixed in the origin of the global coordinate frame.
  • q ̲ 3 W ( Φ ) H 1 describes the posture of joint 3 with respect to the global coordinate frame.
  • q ̲ g R ( Φ g ) = 1 + ε 1 2 p g R r ( Φ g ) H 1 denotes the posture of the end-effector with respect to the local coordinate frame of joint 3.
From Equation (18) it is known that q ̲ g W ( Φ ) = q g p W + ε q g d W = r g W + ε 1 2 p g W r g W H 1 . Using Equations (12), (13), and (17), the end-effector position p g W and orientation o g W can be extracted; therefore, the solution to the forward kinematics problem at any timestep of the gait cycle is given by
ξ g = p g W , o g W = 2 q g d W ( q g p W ) * , 2 ln ( q g p W ) .
Similarly, the forward kinematics solution for each coordinate frame F i is computed using Equation (24) by composing the transformations up to the i-th quaternion and is given by
ξ i = p i W , o i W = 2 q i d W ( q i p W ) * , 2 ln ( q i p W ) .
Algorithm 1 summarizes the method described for the calculation of the forward kinematics solutions [37].
Algorithm 1 Forward kinematics
Require: Body segments parameters p i R , reference joint configurations Φ i , and end-effector dual quaternion q ̲ g R ( Φ g )
n number of joints
for i = 1 , i = n do
    r i R e Φ i
    q ̲ i R ( Φ i ) 1 + ε 1 2 p i R r i R ( Φ i )
    q ̲ i W q ̲ i 1 W q ̲ i R
    p i W 2 q i d W ( q i p W ) *
    o i W 2 ln ( q i p W )
    ξ i [ p i W , o i W ]
end for
q ̲ g W q ̲ n W q ̲ g R
p g W 2 q g d W ( q g p W ) *
o g W 2 ln ( q g p W )
return ξ g [ p g W , o g W ]

2.7. Inverse Kinematics

Let f be the function that determines the end-effector posture vector ξ g given the chain configuration vector Φ ; the inverse kinematics problem can be defined as
Φ f 1 ( ξ g ) ,
which implies that there may not always exist a solution, and when it does, there may not be a unique solution [38]. Nevertheless, it is desirable to find a solution that results in the most natural posture and the most stable behavior. For the case of human lower limbs, this means finding a solution with knee-forward configuration and smooth trajectories. In some cases, it is possible to compute the solution Φ analytically, by trying all possible joint configurations that bring the end-effector closer to the desired posture. For cases where it is not possible to compute an analytical solution, Jacobian-based methods iteratively approximate an effective inverse kinematics solution [25]. The basic equation for forward dynamics that describes the velocities of the end-effector is given by ξ ˙ g = J Φ ˙ , where J is the Jacobian matrix. This can be approximated as a small change in the end-effector posture caused by a small change in joint angles, given by
Δ ξ g ξ g Φ Δ Φ J ( ξ g , Φ ) Δ Φ .
Therefore, the relationship expressed in Equation (27) can be approximated as
Δ Φ J ( ξ g , Φ ) 1 Δ ξ g .
In some cases, the Equation (29) cannot be solved uniquely. Indeed, the Jacobian may not be square or invertible, and even if is invertible, Equation (29) may work poorly if J is near singularity. A recurring problem in tracking target postures is that when the target postures are too distant, the kinematic chain stretches out to try to reach the target position. Once the chain is extended in this way, it is usually near a singularity, that is, the Jacobian is very sensitive to small changes in joint angles, and the chain may shake or jitter, attempting unsuccessfully to reach the distant target [38].
The Damped Least Squares (DLS) Jacobian method addresses many of the singularities problems of other Jacobian methods. DLS works by finding the value of Δ Φ that minimizes the value of
J Δ Φ ξ g 2 + γ 2 Δ Φ ,
where γ is a positive, nonzero damping constant. The solution to the inverse kinematics problem using the DLS method is formally defined as
Δ Φ = J T ( J J T + γ 2 I ) 1 Δ ξ g .
The value of the damping constant γ ( 0 , 1 ) depends on the parameters of the kinematic chain and target postures, which must be set to make the DLS numerically stable. Let Δ ξ g = ζ g ξ g be the error between the current posture ξ g and the target posture ζ g of the end-effector. By definition in Equation (29), the approximation Δ Φ is valid only for small changes Δ ξ g . Therefore, it is convenient to approximate the end-effector posture ξ g to the target posture ζ g only by a step size constant α ( 0 , 1 ) . Then, the incremental posture update is defined as Δ ξ g = α ( ζ g ξ g ) . Thus, the new configuration is as follows:
Φ new = Φ + Δ Φ ,
and leads to a new posture of the end-effector ξ g new = f ( Φ new ) . For ξ g R 6 and Φ R 9 , the Jacobian matrix is given by
J ( ξ g , Φ ) = J p ( Φ ) J o ( Φ ) = ξ g , 1 Φ 1 ξ g , 1 Φ 2 ξ g , 1 Φ 3 ξ g , 6 Φ 1 ξ g , 6 Φ 2 ξ g , 6 Φ 3 R 6 × 9 ,
where ξ g , k Φ i = ξ g , k Φ i , 1 , ξ g , k Φ i , 2 , ξ g , k Φ i , 3 , for i = { 1 , 2 , 3 } , k = { 1 , 2 , , 6 } , are the partial derivatives of the components of the posture vector of the end-effector with respect to the logarithm of r i R ( Φ i ) . In fact, the columns of the Jacobian matrix are given by
ξ g ( Φ ) Φ = p g W ( Φ ) Φ , o g W ( Φ ) Φ .
The calculation of the partial derivatives of p g W and o g W and of the Jacobian matrix is discussed extensively in [27]. At each timestep of the gait cycle, the inverse kinematics method iterates until the norm of the posture error | ζ g ξ g | falls below a selected threshold ϵ , or when the number of iterations exceeds the maximum limit N.

2.8. IK Algorithm Parametrization

To prevent the IK solution from taking values outside the range of motion of the lower limb joints, it is necessary to set limits to the joint angles. Then, any rotation of the joints θ i is clamped as follows:
θ i , clamp = θ i , max , if θ i > θ i , max θ i , otherwise θ i , min , if θ i < θ i , min ,
where the angle θ i is obtained from Equation (32) using θ i = 2 | Φ i new | . The quaternion logarithm with the clamped angle is given by
Φ i , clamp new = 1 2 u θ i , clamp
Table 2 summarizes the angular limits of the joints used in this work [29].
Setting the angles of the the initial chain configuration Φ 0 with the knee in slight flexion ( 5 ) forces a knee-forward solution. While setting the angles of the hip and the ankle joints close to the angle values in the first step of a given gait cycle improves the convergence time of the solution at the beginning of the estimation process. This is particularly visible in the heel-walking initial chain configuration values. The values shown in Table 3 were set heuristically.
The values of the algorithm parameters α and γ were computed by means of a particle swarm optimization algorithm [39,40]. Table 4, shows the numerical values of α and γ for each gait pattern used in this work.
Additionally, to determine the values of ϵ and N, the following was considered: The frequency sampling of the data provided by the authors is 60 Hz [29], which is equivalent to a period of 1.67 × 10 2 s. The resolution of the data was estimated as the minimum difference between all samples, for which the data were first sorted, and repeated values were removed. Then, the difference between contiguous values was calculated. Finally, the minimum difference was computed, the value of which was found to be 1.131 × 10 5 . From Table 5 it can be seen that, for ϵ = 1 × 10 6 , the average computation time per sample is 1.012 × 10 2 s (roughly 99 Hz) and that the average error norm is 7.598 × 10 7 . Both values are adequate given the characteristics of the data. Therefore, we established N = 56 .
The pseudocode in Algorithm 2 presents the way to solve the inverse kinematics problem for a kinematic chain of n DoF. In this work, we use a 3-DoF kinematic chain to model a lower limb on the sagittal plane.
Algorithm 2 Inverse kinematics
Require: Target posture coordinates ζ g , step size factor α , damping factor γ , joint limits θ i , min / max , body segments parameters p i R , initial chain configuration Φ 0 and end-effector dual quaternion q ̲ g R ( Φ g )
ϵ error theshold value
N maximum number of iterations
n number of joints
ξ g 0 f ( Φ 0 )
k 0
while | ζ g ξ g k | > ϵ and k N  do
     J J ( ξ g k , Φ k )
     Δ ξ g k α ( ζ g ξ g k )
     Δ Φ k J T ( J J T + γ 2 I ) 1 Δ ξ g k
     Φ k + 1 Φ + Δ Φ
    for  i = 1 , i = n  do
       Φ i , clamp k + 1 clamp ( Φ i k + 1 )
    end for
     ξ g k + 1 f ( Φ clamp k + 1 )
     k k + 1
end while
return Φ clamp k + 1

3. Results

3.1. Inverse Kinematics

Figure 4 shows the two 3D models used to illustrate the sequential postures of the body segments during the normal gait cycle in the sagittal plane. The blue model motion is reconstructed from the reference joint angles, while the orange model shows the motion obtained from the estimated joint angles of IK. A visual examination suggests that both models reproduce the gait cycle with minimal differences, resulting in an apparent overlap.
Figure 5 illustrates the comparison between the trajectories of the reference and the estimated joint angles during the three types of gait. The plots for toe-walking show that, during the last 10 % of the gait cycle, the estimated hip joint angle estimation raises to the flexion limit, while the estimated knee and ankle joint angles do not reach the magnitude of the reference angles. As for normal gait and heel-walking, the estimated angles follow the trajectories of the reference angles smoothly, with only slight differences.
The accuracy of the inverse kinematics method is assessed by comparing the estimated joint angles with the reference joint angles using the RMSE as a performance metric. The RMSE of the joint angles is less than 8.407 × 10 4 during normal gait and heel-walking and below 2 . 6383 during toe-walking. The highest RMSE corresponds to the knee angles during toe-walking, while the lowest RMSE appears in the hip angles during heel-walking. Table 6 summarizes the RMSE of each joint angle for the different gait types.
A quantitative comparison with a Denavit–Hartenberg (DH) formulation of the DLS algorithm is showed in Table 7. The compared metrics where the average computation time per sample, the average number of iterations per sample, and the average of the three estimated angles’ RMSE. The parameters used for the DH DLS are the same as for the DQ DLS, except for N = 100 .

3.2. Forward Kinematics

In this work, forward kinematics solutions are used to evaluate the effect of the differences between the reference and estimated joint angles on the postures of the anatomical landmarks along the kinematic chain. For this purpose, the trajectories computed by FK1 (using reference joint angles) and FK2 (using estimated joint angles) are compared using the RMSE of the positions of the anatomical landmarks and the RMSE of the orientations of the body segments.
Figure 6 presents a comparison between the Cartesian coordinates on the sagittal plane, computed by FK1 and FK2, for each anatomical landmark across the three types of gait. As expected from the IK results, there are no significant differences in the trajectories of the anatomical landmarks during normal gait and heel-walk. However, the trajectories of the ankle and toe landmarks computed by FK2 show noticeable deviations from those of FK1 during the final part of the cycle.
The RMSE for the positions are below 2.592 × 10 6 m during normal gait and heel-walk, and below 11.1 × 10 3 m during toe-walk. The highest RMSE corresponds to the toe position during toe-walking, while the lowest RMSE appears in the toe position during normal gait. Table 8 summarizes the RMSE values for the position of the anatomical landmarks for each gait type cycle.
Figure 7 shows the comparison of the body segments’ orientations during the three gait types calculated by FK1 and FK2. Femur and tibia orientations during toe-walk show visible differences during the last 10 % of the cycle. The plots also show that the differences in foot orientation during the last part of the toe-walking cycle are less noticeable, as indicated by the RMSE value in Table 9.
The orientation RMSE during normal gait and heel-walk are below 4.592 × 10 4 , while the RMSE for toe-walk reaches 2 . 0105 (Table 9). The highest RMSE corresponds to the tibia orientation during toe-walking, while the lowest RMSE appears in the foot orientation during heel-walking. It is important to note that since the body segments of the three-DoF model rotate within a 2D plane, only rotations about the o z W axis are analyzed.

4. Discussion

In previous works we addressed the solution of the forward kinematics problem to determine only the position of anatomical landmarks [26] and a geometric approach to estimate the joint coordinates [17]. This was useful for a first approximation but results in an incomplete description. In order to provide a complete solution, that is, a solution that not only describes the anatomical landmark positions at the knee, ankle, and hip but also that quantifies the angular variations of the joints and body segments in the sagittal plane, in the present study two main objectives were set. First, it aims to develop a framework for kinematic gait analysis using a dual-quaternions composition to solve the forward kinematics problem and the DLS Jacobian method for the inverse kinematics problem. Second, it seeks to assess whether the proposed method is applicable to different types of gait whose characteristics resemble those seen in pathological gait patterns.
Regarding the development of the proposed framework, the algebraic formulation presented in Section 2 supports the reliability of the forward kinematics solution. Other representation formalisms, such as unit quaternions, Euler angles, and angle–axis representations in combination with 3D vectors, describe rotation and translation independently, which may result in a loss of coupling between rotation and translation [41]. In contrast, dual-quaternion operations have been widely demonstrated to provide a unified and formally valid representation of rigid body transformations in three-dimensional Euclidean space, effectively integrating rotation and translation [23]. Dual quaternions also avoid discontinuities and singularities that arise from the Euler angle representation, such as the phenomenon of gimbal lock [42], and can be used to generate fast reliable IK solutions in real-time for highly articulated models [43].
Furthermore, dual quaternions offer some advantages in representing human motion in gait analysis compared to homogeneous transformation matrices. Dual quaternions can be easily concatenated, interpolated smoothly, and provide rigid transform comparisons effortlessly [43], but more important, they are a compact representation, using only eight parameters to represent both rotation and translation, while homogeneous matrices require twelve parameters [42], which also reduces the number of algebraic operations for kinematic modeling applications [41].
On the other hand, Figure 5, Figure 6 and Figure 7 serve to highlight the differences in joint angles, anatomical landmark positions, and segment orientations over the three types of gait analyzed. In toe-walking, hip extension and knee flexion are reduced, and ankle dorsiflexion is absent. While, heel-walking is characterized by a lack of hip extension, reduced knee flexion, and decreased ankle plantarflexion. These gait abnormalities are features of pathological gaits seen in disease conditions such as cerebral palsy [44], Parkinson’s disease [45], and post-stroke hemiplegia [46]. Gait deviations exhibited in impairments such as the aforementioned tend to be a continuum of deviations rather than distinct categories. Therefore, an accurate description of individual gait deviations, rather than a group classification, may provide better guidance for the development and customization of therapeutic treatments.
The RMSE data summarized in Table 6, Table 8, and Table 9 show that, in general, both the estimated angles and the computed end-effector postures are close to the reference joint angles and to the target postures, respectively, for all gait types analyzed. Consequently, we consider that the proposed approach holds potential for gait analysis in clinical settings and that it can be applied to identify and quantify motor deficits, as well as to provide an objective assessment of gait treatments [47].
Quantitative comparison of the proposed DLS algorithm with a Denavit–Hartenberg formulation shown in Table 7 exhibit an improvement in computation time per sample, and a reduction in the number of iterations and on the average of the RMSE of the estimated angles in all gait types except for the toe-walking pattern. Therefore, further optimization of the algorithm and its parameters must be realized in order to solve the visible problems that limit the current performance of the proposed method.

Limitations

The presented IK method performs the estimations of the joint angles based only on the foot segment postures. Although in some cases this does not make it difficult to obtain an anatomically correct IK solution; in some other cases this results in the need for conditions to force a solution with a forward knee configuration and ensure fast convergence time at the beginning of the estimation process. The first condition is the need to impose an initial posture different from the anatomical posture. The initial postures used in this work are based on the rotation of the joints in the first step of the gait pattern analyzed. Currently, there is no general posture that is applicable for all different types of gait, but that would be desirable. In fact, in the case of heel-walking, to ensure fast convergence time at the beginning of the estimation process, it was necessary to set the initial estimated posture very close to the initial target posture.
The second condition is the need to impose joint limits close to the limits of the specific range of motion of the gait type being analyzed. The toe-walking gait cycle is an example of this scenario. A close look at Figure 5 reveals a deviation of the estimated angles during the last 10 % of the toe-walking gait cycle. The effects of this angular deviation are reflected in the positions of the anatomical landmarks and in the orientations of the body segments, as shown in Figure 6 and Figure 7, respectively. Although the imposition of joint limits helped to considerably reduce this deviation, it was not possible to eliminate it completely.

5. Conclusions

In this paper we presented a framework for solving forward and inverse kinematics problems, applied to two-dimensional gait analysis of a three-DoF model of the human lower limb. However, due to the generality of the formulation, the method can be extended to the analysis of kinematic chains with more degrees of freedom and multiple end-effectors, as would be the case of a model of the human body representing the motion of all its limbs in three dimensions. Furthermore, we consider that the proposed algorithms could be used in diverse scenarios such as performance evaluation in sports or in the clinical diagnosis of motor deficits. In particular, the results demonstrate that diseases that share characteristics with toe-walking and heel-walking, such as cerebral palsy, Parkinson’s disease, or post-stroke hemiplegia could be analyzed using the proposed method.
Despite the encouraging results, a rigorous comparison with other numerical methods and IK solvers is still needed. In addition, a review of novel methods, such as those based on machine learning, could provide useful tools to generalize the results and reduce the need for specific parameterizations for each type of motion. Finally, it is necessary to consider the inclusion of more diverse data and therefore the development of the necessary methods for the acquisition and processing of data from different types of sensors for the recording of gait kinematic data.

Author Contributions

Conceptualization, R.V.-H. and J.-C.G.-I.; methodology, R.V.-H. and J.-C.G.-I.; software, R.V.-H. and R.S.-C.; validation, J.-C.G.-I. and O.-A.D.-R.; formal analysis, R.V.-H., J.-C.G.-I. and O.-A.D.-R.; investigation, R.V.-H., J.-C.G.-I. and E.R.-S.; resources, J.-C.G.-I. and O.-A.D.-R.; data curation, E.R.-S. and R.S.-C.; writing—original draft preparation, R.V.-H. and J.-C.G.-I.; writing—review and editing, O.-A.D.-R., E.R.-S. and R.S.-C.; visualization, R.V.-H. and R.S.-C.; supervision, J.-C.G.-I. and O.-A.D.-R.; project administration, R.V.-H. and J.-C.G.-I.; funding acquisition, E.R.-S. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The original contributions presented in this study are included in this article; further inquiries can be directed to the corresponding author.

Acknowledgments

The first and fifth authors are grateful to SECIHTI of Mexico for granting the scholarship with support number: 4045813 and 2052032, respectively. The second, third and fourth authors are thankful to the Autonomous University of the State of Hidalgo and the SNII of the SECIHTI of Mexico.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Richards, J.; Levine, D.; Whittle, M.W. Whittle’s Gait Analysis-E-Book: Whittle’s Gait Analysis-E-Book; Elsevier Health Sciences: Amsterdam, The Netherlands, 2022. [Google Scholar]
  2. Stergiou, N. Biomechanics and Gait Analysis; Academic Press: Cambridge, MA, USA, 2020. [Google Scholar]
  3. Khera, P.; Kumar, N. Role of machine learning in gait analysis: A review. J. Med. Eng. Technol. 2020, 44, 441–467. [Google Scholar] [CrossRef] [PubMed]
  4. Kanko, R.M.; Laende, E.K.; Davis, E.M.; Selbie, W.S.; Deluzio, K.J. Concurrent assessment of gait kinematics using marker-based and markerless motion capture. J. Biomech. 2021, 127, 110665. [Google Scholar] [CrossRef] [PubMed]
  5. Niku, S.B. Introduction to Robotics: Analysis, Control, Applications; John Wiley & Sons: Hoboken, NJ, USA, 2020. [Google Scholar]
  6. Jiang, C.; Liu, X.; Su, Q.; Huang, D.; Tu, X.; Ke, X.; Lin, Z. Gait kinematic and kinetic characteristics among older adults with varying degrees of frailty: A cross-sectional study. Sci. Rep. 2025, 15, 10915. [Google Scholar] [CrossRef] [PubMed]
  7. Guffanti, D.; Brunete, A.; Hernando, M.; Rueda, J.; Navarro, E. ROBOGait: A mobile robotic platform for human gait analysis in clinical environments. Sensors 2021, 21, 6786. [Google Scholar] [CrossRef]
  8. Roy, G.; Mukherjee, S.; Das, T.; Bhaumik, S. Single support phase gait kinematics and kinetics for a humanoid lower limb exoskeleton. In Proceedings of the 2020 IEEE Region 10 Symposium (TENSYMP), Dhaka, Bangladesh, 5–7 June 2020; pp. 138–141. [Google Scholar]
  9. Cardona, M.; Garcia Cena, C.E.; Serrano, F.; Saltaren, R. ALICE: Conceptual development of a lower limb exoskeleton robot driven by an on-board musculoskeletal simulator. Sensors 2020, 20, 789. [Google Scholar] [CrossRef]
  10. Dewolf, A.H.; Sylos-Labini, F.; Cappellini, G.; Lacquaniti, F.; Ivanenko, Y. Emergence of different gaits in infancy: Relationship between developing neural circuitries and changing biomechanics. Front. Bioeng. Biotechnol. 2020, 8, 473. [Google Scholar] [CrossRef]
  11. Ogihara, H.; Tsushima, E.; Kamo, T.; Sato, T.; Matsushima, A.; Niioka, Y.; Asahi, R.; Azami, M. Kinematic gait asymmetry assessment using joint angle data in patients with chronic stroke—A normalized cross-correlation approach. Gait Posture 2020, 80, 168–173. [Google Scholar] [CrossRef]
  12. Pyrzanowska, W.; Chrościńska-Krawczyk, M.; Bonikowski, M. Long-Term Improvement of Gait Kinematics in Young Children with Cerebral Palsy Treated with Botulinum Toxin Injections and Integrated/Intensive Rehabilitation: A 5-Year Retrospective Observational Study. Toxins 2025, 17, 142. [Google Scholar] [CrossRef]
  13. Spong, M.W. Robot motion control. In Encyclopedia of Systems and Control; Springer: Berlin/Heidelberg, Germany, 2021; pp. 1901–1911. [Google Scholar]
  14. Morecki, A.; Knapczyk, J. Manipulator Kinematics. In Basics of Robotics: Theory and Components of Manipulators and Robots; Springer: Berlin/Heidelberg, Germany, 1999; pp. 34–54. [Google Scholar]
  15. Siciliano, B.; Sciavicco, L.; Villani, L.; Oriolo, G. Kinematics. In Robotics: Modelling, Planning and Control; Springer: Berlin/Heidelberg, Germany, 2009; pp. 39–103. [Google Scholar]
  16. Jazar, R.N. Inverse Kinematics. In Theory of Applied Robotics: Kinematics, Dynamics, and Control; Springer: Berlin/Heidelberg, Germany, 2021; pp. 313–358. [Google Scholar]
  17. Gonzalez-Islas, J.C.; Dominguez-Ramirez, O.A.; Lopez-Ortega, O.; Peña-Ramirez, J.; Ordaz-Oliver, J.P.; Marroquin-Gutierrez, F. Crouch gait analysis and visualization based on gait forward and inverse kinematics. Appl. Sci. 2022, 12, 10197. [Google Scholar] [CrossRef]
  18. Abdor-Sierra, J.A.; Merchán-Cruz, E.A.; Rodríguez-Cañizo, R.G. A comparative analysis of metaheuristic algorithms for solving the inverse kinematics of robot manipulators. Results Eng. 2022, 16, 100597. [Google Scholar] [CrossRef]
  19. Ahmed, A.; Yu, M.; Chen, F. Inverse kinematic solution of 6-DOF robot-arm based on dual quaternions and axis invariant methods. Arab. J. Sci. Eng. 2022, 47, 15915–15930. [Google Scholar] [CrossRef]
  20. Chelnokov, Y.N. Orientation and kinematics of rotation: Quaternionic and four-dimensional skew-symmetric operators, equations, and algorithms. Mech. Solids 2022, 57, 1885–1907. [Google Scholar] [CrossRef]
  21. Cohen, A.; Shoham, M. Hyper Dual Quaternions representation of rigid bodies kinematics. Mech. Mach. Theory 2020, 150, 103861. [Google Scholar] [CrossRef]
  22. Luo, J.; Chen, S.; Zhang, C.; Chen, C.Y.; Yang, G. Efficient kinematic calibration for articulated robot based on unit dual quaternion. IEEE Trans. Ind. Inform. 2023, 19, 11898–11909. [Google Scholar] [CrossRef]
  23. Dantam, N.T. Robust and efficient forward, differential, and inverse kinematics using dual quaternions. Int. J. Robot. Res. 2021, 40, 1087–1105. [Google Scholar] [CrossRef]
  24. Wang, L.; Song, Z.; You, J.; Li, Y.; Wu, H. A fast forward kinematics algorithm based on planar quaternion solution for a class of 3-DoF planar parallel mechanisms. Meccanica 2024, 59, 461–473. [Google Scholar] [CrossRef]
  25. Kenwright, B. Inverse kinematics with dual-quaternions, exponential-maps, and joint limits. arXiv 2022, arXiv:2211.01466. [Google Scholar]
  26. González-Islas, J.; Domínguez-Ramírez, O.A.; López-Ortega, O. Biped gait analysis based on forward kinematics modeling using quaternions algebra. Rev. Mex. Ing. Biomed. 2020, 41, 56–71. [Google Scholar]
  27. Vergara-Hernández, R.; Magaña-Méndez, M.A.; Ramos-Fernández, J.C.; Hernández-Cortés, T. Análisis cinemático utilizando cuaterniones duales. PÄDi Bol. Cient. Cienc. Basicas Ing. ICBI 2023, 10, 52–60. [Google Scholar] [CrossRef]
  28. Schwung, A.; Pöppelbaum, J.; Nutakki, P.C. Rigid Body Movement Prediction Using Dual Quaternion Recurrent Neural Networks. In Proceedings of the 2021 22nd IEEE International Conference on Industrial Technology (ICIT), Valencia, Spain, 10–12 March 2021; Volume 1, pp. 756–761. [Google Scholar] [CrossRef]
  29. Bovi, G.; Rabuffetti, M.; Mazzoleni, P.; Ferrarin, M. A multiple-task gait analysis approach: Kinematic, kinetic and EMG reference data for healthy young and adult subjects. Gait Posture 2011, 33, 6–13. [Google Scholar] [CrossRef]
  30. Thomas, S.J.; Zeni, J.A.; Winter, D.A. Winter’s Biomechanics and Motor Control of Human Movement; John Wiley & Sons: Hoboken, NJ, USA, 2022. [Google Scholar]
  31. Avila-Chaurand, R.; Prado-León, L.; González-Muñoz, E. Dimensiones antropométricas de población latinoamericana: México, Cuba, Colombia, Chile. In Avila Chaurand, LR Prado León, EL González Muñoz; Universidad de Guadalajara: Guadalajara, Mexico, 2007. [Google Scholar]
  32. Familton, J.C. Quaternions: A History of Complex Noncommutative Rotation Groups in Theoretical Physics; Columbia University: New York, NY, USA, 2015. [Google Scholar]
  33. Adorno, B.V. Robot Kinematic Modeling and Control Based on Dual Quaternion Algebra—Part I: Fundamentals. 2017; preprints. [Google Scholar]
  34. Kuipers, J.B. Quaternions and Rotation Sequences: A Primer with Applications to Orbits, Aerospace, and Virtual Reality; Princeton University Press: Princeton, NJ, USA, 1999. [Google Scholar]
  35. Dam, E.B.; Koch, M.; Lillholm, M. Quaternions, Interpolation and Animation; University of Copenhagen: Copenhagen, Denmark, 1998; Volume 2. [Google Scholar]
  36. Sola, J. Quaternion kinematics for the error-state Kalman filter. arXiv 2017, arXiv:1711.02508. [Google Scholar]
  37. Bartelink, M. Global Inverse Kinematics Solver for Linked Mechanisms Under Joint Limits and Contacts. Master’s Thesis, Utrecht University, Utrecht, The Netherlands, 2012. [Google Scholar]
  38. Buss, S.R. Introduction to inverse kinematics with jacobian transpose, pseudoinverse and damped least squares methods. IEEE J. Robot. Autom. 2004, 17, 16. [Google Scholar]
  39. Kennedy, J.; Eberhart, R. Particle swarm optimization. In Proceedings of the ICNN’95-International Conference on Neural Networks, Perth, WA, Australia, 27 November–1 December 1995; Volume 4, pp. 1942–1948. [Google Scholar]
  40. Wang, D.; Tan, D.; Liu, L. Particle swarm optimization algorithm: An overview. Soft Comput. 2018, 22, 387–408. [Google Scholar] [CrossRef]
  41. Wang, X.; Zhu, H. On the comparisons of unit dual quaternion and homogeneous transformation matrix. Adv. Appl. Clifford Algebr. 2014, 24, 213–229. [Google Scholar] [CrossRef]
  42. Benhmidouch, Z.; Moufid, S.; Omar, A.A. Kinematics and dynamics modeling of 7 degrees of freedom human lower limb using dual quaternions algebra. arXiv 2023, arXiv:2302.11605. [Google Scholar]
  43. Kenwright, B. A survey on dual-quaternions. arXiv 2023, arXiv:2303.14765. [Google Scholar]
  44. Bonanno, M.; Militi, A.; La Fauci Belponer, F.; De Luca, R.; Leonetti, D.; Quartarone, A.; Ciancarelli, I.; Morone, G.; Calabro, R.S. Rehabilitation of Gait and Balance in Cerebral Palsy: A scoping review on the Use of Robotics with Biomechanical implications. J. Clin. Med. 2023, 12, 3278. [Google Scholar] [CrossRef]
  45. Zanardi, A.P.J.; da Silva, E.S.; Costa, R.R.; Passos-Monteiro, E.; Dos Santos, I.O.; Kruel, L.F.M.; Peyré-Tartaruga, L.A. Gait parameters of Parkinson’s disease compared with healthy controls: A systematic review and meta-analysis. Sci. Rep. 2021, 11, 752. [Google Scholar] [CrossRef]
  46. Li, S.; Francisco, G.E.; Zhou, P. Post-stroke hemiplegic gait: New perspective and insights. Front. Physiol. 2018, 9, 1021. [Google Scholar] [CrossRef] [PubMed]
  47. Armand, S.; Decoulon, G.; Bonnefoy-Mazure, A. Gait analysis in children with cerebral palsy. EFORT Open Rev. 2016, 1, 448–460. [Google Scholar] [CrossRef]
Figure 1. General framework for modeling a 3-DoF kinematic chain for two-dimensional gait analysis.
Figure 1. General framework for modeling a 3-DoF kinematic chain for two-dimensional gait analysis.
Jfmk 10 00298 g001
Figure 2. Representation of a unit quaternion as the radius of a unit circle in the complex plane. The coordinates are the scalar part q 0 and the norm of the vector part | q | in the R and I axes, respectively.
Figure 2. Representation of a unit quaternion as the radius of a unit circle in the complex plane. The coordinates are the scalar part q 0 and the norm of the vector part | q | in the R and I axes, respectively.
Jfmk 10 00298 g002
Figure 3. Right lower limb modeled as a 3-Degrees of Freedom (DoF) kinematic chain. (a) Joint local coordinate frames and body segment distances. (b) Axis–angle pair of each joint. (c) 3D model based on the body segment parameters. The x, y, and z axes of the local coordinate frames are indicated by the red, green, and blue arrows, respectively.
Figure 3. Right lower limb modeled as a 3-Degrees of Freedom (DoF) kinematic chain. (a) Joint local coordinate frames and body segment distances. (b) Axis–angle pair of each joint. (c) 3D model based on the body segment parameters. The x, y, and z axes of the local coordinate frames are indicated by the red, green, and blue arrows, respectively.
Jfmk 10 00298 g003
Figure 4. Normal gait cycle reproduced by two superimposed 3D lower limb models using the reference joint angles (blue model) and the estimated joint angles computed through inverse kinematics (orange model).
Figure 4. Normal gait cycle reproduced by two superimposed 3D lower limb models using the reference joint angles (blue model) and the estimated joint angles computed through inverse kinematics (orange model).
Jfmk 10 00298 g004
Figure 5. Comparison of the reference (R, dashed lines) and estimated (E, ∘ markers) joint angles for the hip, knee, and ankle joints during normal Gait (N), toe-walking (TW), and heel-walking (HW) cycles. Vertical dashed black line indicates the 60% of the gait cycle.
Figure 5. Comparison of the reference (R, dashed lines) and estimated (E, ∘ markers) joint angles for the hip, knee, and ankle joints during normal Gait (N), toe-walking (TW), and heel-walking (HW) cycles. Vertical dashed black line indicates the 60% of the gait cycle.
Jfmk 10 00298 g005
Figure 6. Comparison of the trajectories of the anatomical landmarks using the reference joint angles ( FK 1 ) (dashed line) and the joint angles obtained using inverse kinematics ( FK 2 ) (∘ colorbar). Where, the vertical right colorbar is the percentage of the gait cycle.
Figure 6. Comparison of the trajectories of the anatomical landmarks using the reference joint angles ( FK 1 ) (dashed line) and the joint angles obtained using inverse kinematics ( FK 2 ) (∘ colorbar). Where, the vertical right colorbar is the percentage of the gait cycle.
Jfmk 10 00298 g006
Figure 7. Comparison of the orientation of the body segments with respect to the global coordinate system during normal gait (N), toe-walking (TW), and heel-walking (HW) cycles; calculated using FK1 (dashed line) and FK2 (∘ line). Vertical dashed black line marks the 60% of the gait cycle.
Figure 7. Comparison of the orientation of the body segments with respect to the global coordinate system during normal gait (N), toe-walking (TW), and heel-walking (HW) cycles; calculated using FK1 (dashed line) and FK2 (∘ line). Vertical dashed black line marks the 60% of the gait cycle.
Jfmk 10 00298 g007
Table 1. Parameters of the body segments.
Table 1. Parameters of the body segments.
ParameterLength
Body height1.65 m
Femur length0.37 m
Tibia length0.38 m
Lateral malleolus height0.08 m
LM-to-DPH0.25 m
Table 2. Angular limits of the joints.
Table 2. Angular limits of the joints.
MotionLimitNormal GaitToe-WalkingHeel-Walking
Hip flexion θ 1 , max 180 33 . 6 34 . 3
Hip extension θ 1 , min 180 6 . 4 7 . 5
Knee extension θ 2 , max 180 5 . 6 8 . 2
Knee flexion θ 2 , min 180 50 . 4 25 . 8
Ankle dorsiflx. θ 2 , max 180 7 . 6 19 . 2
Ankle plantarflx. θ 2 , min 180 32 . 3 9
Table 3. Initial chain configuration values.
Table 3. Initial chain configuration values.
JointNormal GaitToe-WalkingHeel-Walking
Hip 1 1 32
Knee 5 5 5
Ankle 1 1 12
Table 4. IK algorithm parameter values.
Table 4. IK algorithm parameter values.
ParameterNormal GaitToe-WalkingHeel-Walking
α 0.6992 0.7334 0.7301
γ 0.0579 0.0608 0.0579
Table 5. Relationship between ϵ , the number of iterations, and the error values.
Table 5. Relationship between ϵ , the number of iterations, and the error values.
ϵ Avrg. Time per Sample (s)Min. of IterationsMax. of IterationsAvrg. Error Norm
1 × 10 0 1.482 × 10 4 12 4.355 × 10 1
1 × 10 1 2.956 × 10 4 14 5.824 × 10 2
1 × 10 2 1.624 × 10 3 118 5.164 × 10 3
1 × 10 3 2.714 × 10 3 334 6.985 × 10 4
1 × 10 4 4.905 × 10 3 579 7.425 × 10 5
1 × 10 5 7.672 × 10 3 535 7.465 × 10 6
1 × 10 6 1.012 × 10 2 1056 7.598 × 10 7
1 × 10 7 1.307 × 10 2 1283 7.336 × 10 8
1 × 10 8 1.623 × 10 2 14125 7.526 × 10 9
1 × 10 9 1.942 × 10 2 16167 7.591 × 10 10
Table 6. RMSE of the comparison between the references and estimated joint angles.
Table 6. RMSE of the comparison between the references and estimated joint angles.
JointNormal GaitToe-WalkingHeel-Walking
Hip 3.825 × 10 4 0 . 6593 2.558 × 10 4
Knee 8.407 × 10 4 2 . 6383 6.234 × 10 4
Ankle 4.584 × 10 4 1 . 6130 3.661 × 10 4
Table 7. Comparison between Denavit–Hartenberg (DH) and dual quaternion (DQ) formulation for joint angles estimation using DLS algorithm.
Table 7. Comparison between Denavit–Hartenberg (DH) and dual quaternion (DQ) formulation for joint angles estimation using DLS algorithm.
MetricNormal Gait DQNormal Gait DHToe-Walking DQToe-Walking DHHeel-Walking DQHeel-Walking DH
Avg. time per sample 0.011 0.063 0.019 0.062 0.0102 0.054
Avg. n. of iterations199635952090
Avr. angle error 5.6054 × 10 4 8.3113 × 10 4 2.167 3.704 × 10 4 4.142 × 10 4 5.483 × 10 4
Table 8. RMSE of the position comparison of the anatomical landmarks.
Table 8. RMSE of the position comparison of the anatomical landmarks.
Anatomical LandmarkNormal GaitToe-WalkingHeel-Walking
Knee 2.592 × 10 6 m 4.4 × 10 3 m 1.743 × 10 6 m
Ankle 0.724 × 10 6 m 9.8 × 10 3 m 0.810 × 10 6 m
Toe 0.708 × 10 6 m 11.1 × 10 3 m 0.807 × 10 6 m
Table 9. RMSE of the comparison of the orientation of the body segments.
Table 9. RMSE of the comparison of the orientation of the body segments.
Body SegmentNormal GaitToe-WalkingHeel-Walking
Femur 3.808 × 10 4 0 . 6531 2.560 × 10 4
Tibia 4.592 × 10 4 2 . 0105 3.685 × 10 4
Foot 0.198 × 10 4 0 . 4456 0.045 × 10 4
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Vergara-Hernandez, R.; Gonzalez-Islas, J.-C.; Dominguez-Ramirez, O.-A.; Rueda-Soriano, E.; Serrano-Chavez, R. Dual Quaternion-Based Forward and Inverse Kinematics for Two-Dimensional Gait Analysis. J. Funct. Morphol. Kinesiol. 2025, 10, 298. https://doi.org/10.3390/jfmk10030298

AMA Style

Vergara-Hernandez R, Gonzalez-Islas J-C, Dominguez-Ramirez O-A, Rueda-Soriano E, Serrano-Chavez R. Dual Quaternion-Based Forward and Inverse Kinematics for Two-Dimensional Gait Analysis. Journal of Functional Morphology and Kinesiology. 2025; 10(3):298. https://doi.org/10.3390/jfmk10030298

Chicago/Turabian Style

Vergara-Hernandez, Rodolfo, Juan-Carlos Gonzalez-Islas, Omar-Arturo Dominguez-Ramirez, Esteban Rueda-Soriano, and Ricardo Serrano-Chavez. 2025. "Dual Quaternion-Based Forward and Inverse Kinematics for Two-Dimensional Gait Analysis" Journal of Functional Morphology and Kinesiology 10, no. 3: 298. https://doi.org/10.3390/jfmk10030298

APA Style

Vergara-Hernandez, R., Gonzalez-Islas, J.-C., Dominguez-Ramirez, O.-A., Rueda-Soriano, E., & Serrano-Chavez, R. (2025). Dual Quaternion-Based Forward and Inverse Kinematics for Two-Dimensional Gait Analysis. Journal of Functional Morphology and Kinesiology, 10(3), 298. https://doi.org/10.3390/jfmk10030298

Article Metrics

Back to TopTop