Estimating Lower Limb Kinematics using a Lie Group ...

8
Estimating Lower Limb Kinematics using a Lie Group Constrained EKF and a Reduced Wearable IMU Count Luke Sy Student Member, IEEE, Nigel H. Lovell Fellow, IEEE, Stephen J. Redmond Senior Member, IEEE Abstract— This paper presents an algorithm that makes novel use of Lie group representation of position and orientation alongside a constrained extended Kalman filter (CEKF) for accurately estimating pelvis, thigh, and shank kinematics dur- ing walking using only three wearable inertial sensors. The algorithm iterates through the prediction update (kinematic equation), measurement update (pelvis height, zero velocity update, flat-floor assumption, and covariance limiter), and constraint update (formulation of hinged knee joints and ball- and-socket hip joints). Evaluation of the algorithm on nine healthy subjects who walked freely within a 4 × 4m 3 room shows that it can track motion relative to the mid-pelvis origin with mean position and orientation root-mean-square error of 5.75 ± 1.4 cm and 19.8 ± 5.2 , respectively. The sagittal knee and hip joint angle correlation coefficients were 0.88 ± 0.1 and 0.77 ± 0.1. This paper demonstrate an application of Lie group representation for inertial motion capture. Furthermore, the algorithm can compute gait parameters in real-time and, hence, can be used to inform gait assistive devices. I. I NTRODUCTION Human pose estimation involves tracking the position and orientation of body segments, and estimating joint angles. It finds application in robotics, virtual reality, animation, and healthcare (e.g., gait analysis). Recent miniaturization of inertial measurements units (IMUs) has paved the path toward inertial motion capture systems (IMCs) suitable for use in unstructured environments. Comprehensive commer- cial IMCs attach one sensor per body segment (OSPS) (i.e., five sensors to track the pelvis, thighs, and shanks) [1, 2]. In general, human pose estimation algorithms estimate ori- entation through integration of measured angular rate while using gravity and magnetic north to correct numerical and other (sensor noise and bias) integration errors, and estimate position by either double integration of the measured acceler- ation, or by vector addition of segment axes where segments make a kinematic chain [3, 4]. However, the number of IMUs required to be attached by OSPS configurations might be considered too cumbersome and expensive for routine daily use by a consumer market. A reduced-sensor-count (RSC) configuration, where IMUs are placed on a subset of body segments, can improve user comfort while also reducing setup time and system cost. However, utilizing fewer sensors inherently reduces the amount of kinematic information available; this information must be inferred by enforcing mechanical joint constraints or dynamic balance assumptions. Gait analysis using IMCs has been shown to help diagnose movement disorders and assess surgical outcomes [5]. Developing a comfortable IMC for routine daily use may facilitate interactive rehabilitation/performance improvement [6, 7], and possibly to the study of movement disorder progression to enable predictive diagnostics. This paper describes an algorithm that utilizes Lie group representations of body segment position and orientation, and an iterative estimator for pose estimation using an RSC configuration. A. Lie group representation for pose estimation Valid human body poses can be elegantly represented on a curved geometry (or manifold) embedded within the complete space of all possible body segments configurations. In particular, body segment translation and rotation can be represented using matrix Lie groups, specifically the special orthogonal group, SO(n), and special Euclidean group, SE(n), where n = 2, 3. The matrix Lie group representation of pose (i.e., orientation and position) does not suffer from gimbal lock leading to significant improvement in tracking accuracy [8], and has been used in conjunction with different kind of iterative estimators such as extended Kalman filter (EKF) [9] and unscented Kalman filter (UKF) [10]. Vemulapalli et al. represented the skeleton using a Lie group SE(3) ×···× SE(3) and then performed activity classification in the corresponding Lie algebra vector space [11]. Barfoot et al. derived and demonstrated the propagation of uncertainty in the Lie group SE(3), specifically, through a nonlinear stereo camera [12]. Cesic et al. employed a Lie group EKF to track the full body pose representing the state with SO(2), SO(3), SE(3), and using measurement updates from 3D marker positions [8]. B. Pose estimators under RSC configuration Pose estimators for an RSC configuration can represent the body in various ways. Joint position is usually represented in R 3 . Body segment orientation can be represented using Euler angles, rotation matrices, or quaternions. Below are similar literature that reconstruct body motion using kinematic and biomechanical models for RSC configurations. Hu et al. tracked the pelvis and ankle positions from four IMUs (two at pelvis and one for each foot), and calculated the joint angles using 2D inverse kinematics by modelling each leg as three linked segments confined in the sagittal plane [13]. Marcard et al. modelled the body as a kinematic chain of rigid seg- ments linked by 24 ball and socket joints, and calculated the pose that best matches the six IMU measurements located on the head, wrists, pelvis, and ankles, while satisfying multiple joint angle constraints [14]. The accuracy was impressive, but it has long computation time. Sy et al. tracked the pose of the pelvis, thigh, and shanks from three IMUs at the arXiv:1910.01808v1 [cs.RO] 4 Oct 2019

Transcript of Estimating Lower Limb Kinematics using a Lie Group ...

Estimating Lower Limb Kinematics usinga Lie Group Constrained EKF and a Reduced Wearable IMU Count

Luke Sy Student Member, IEEE, Nigel H. Lovell Fellow, IEEE, Stephen J. Redmond Senior Member, IEEE

Abstract— This paper presents an algorithm that makes noveluse of Lie group representation of position and orientationalongside a constrained extended Kalman filter (CEKF) foraccurately estimating pelvis, thigh, and shank kinematics dur-ing walking using only three wearable inertial sensors. Thealgorithm iterates through the prediction update (kinematicequation), measurement update (pelvis height, zero velocityupdate, flat-floor assumption, and covariance limiter), andconstraint update (formulation of hinged knee joints and ball-and-socket hip joints). Evaluation of the algorithm on ninehealthy subjects who walked freely within a 4 × 4m3 roomshows that it can track motion relative to the mid-pelvis originwith mean position and orientation root-mean-square error of5.75 ± 1.4 cm and 19.8 ± 5.2, respectively. The sagittal kneeand hip joint angle correlation coefficients were 0.88± 0.1 and0.77±0.1. This paper demonstrate an application of Lie grouprepresentation for inertial motion capture. Furthermore, thealgorithm can compute gait parameters in real-time and, hence,can be used to inform gait assistive devices.

I. INTRODUCTION

Human pose estimation involves tracking the position andorientation of body segments, and estimating joint angles.It finds application in robotics, virtual reality, animation,and healthcare (e.g., gait analysis). Recent miniaturizationof inertial measurements units (IMUs) has paved the pathtoward inertial motion capture systems (IMCs) suitable foruse in unstructured environments. Comprehensive commer-cial IMCs attach one sensor per body segment (OSPS) (i.e.,five sensors to track the pelvis, thighs, and shanks) [1, 2].In general, human pose estimation algorithms estimate ori-entation through integration of measured angular rate whileusing gravity and magnetic north to correct numerical andother (sensor noise and bias) integration errors, and estimateposition by either double integration of the measured acceler-ation, or by vector addition of segment axes where segmentsmake a kinematic chain [3, 4]. However, the number ofIMUs required to be attached by OSPS configurations mightbe considered too cumbersome and expensive for routinedaily use by a consumer market. A reduced-sensor-count(RSC) configuration, where IMUs are placed on a subsetof body segments, can improve user comfort while alsoreducing setup time and system cost. However, utilizingfewer sensors inherently reduces the amount of kinematicinformation available; this information must be inferred byenforcing mechanical joint constraints or dynamic balanceassumptions. Gait analysis using IMCs has been shownto help diagnose movement disorders and assess surgicaloutcomes [5]. Developing a comfortable IMC for routinedaily use may facilitate interactive rehabilitation/performance

improvement [6, 7], and possibly to the study of movementdisorder progression to enable predictive diagnostics.

This paper describes an algorithm that utilizes Lie grouprepresentations of body segment position and orientation,and an iterative estimator for pose estimation using an RSCconfiguration.

A. Lie group representation for pose estimation

Valid human body poses can be elegantly representedon a curved geometry (or manifold) embedded within thecomplete space of all possible body segments configurations.In particular, body segment translation and rotation canbe represented using matrix Lie groups, specifically thespecial orthogonal group, SO(n), and special Euclideangroup, SE(n), where n = 2, 3. The matrix Lie grouprepresentation of pose (i.e., orientation and position) does notsuffer from gimbal lock leading to significant improvementin tracking accuracy [8], and has been used in conjunctionwith different kind of iterative estimators such as extendedKalman filter (EKF) [9] and unscented Kalman filter (UKF)[10]. Vemulapalli et al. represented the skeleton using a Liegroup SE(3) × · · · × SE(3) and then performed activityclassification in the corresponding Lie algebra vector space[11]. Barfoot et al. derived and demonstrated the propagationof uncertainty in the Lie group SE(3), specifically, througha nonlinear stereo camera [12]. Cesic et al. employed a Liegroup EKF to track the full body pose representing the statewith SO(2), SO(3), SE(3), and using measurement updatesfrom 3D marker positions [8].

B. Pose estimators under RSC configuration

Pose estimators for an RSC configuration can represent thebody in various ways. Joint position is usually represented inR3. Body segment orientation can be represented using Eulerangles, rotation matrices, or quaternions. Below are similarliterature that reconstruct body motion using kinematic andbiomechanical models for RSC configurations. Hu et al.tracked the pelvis and ankle positions from four IMUs (two atpelvis and one for each foot), and calculated the joint anglesusing 2D inverse kinematics by modelling each leg as threelinked segments confined in the sagittal plane [13]. Marcardet al. modelled the body as a kinematic chain of rigid seg-ments linked by 24 ball and socket joints, and calculated thepose that best matches the six IMU measurements located onthe head, wrists, pelvis, and ankles, while satisfying multiplejoint angle constraints [14]. The accuracy was impressive,but it has long computation time. Sy et al. tracked the poseof the pelvis, thigh, and shanks from three IMUs at the

arX

iv:1

910.

0180

8v1

[cs

.RO

] 4

Oct

201

9

pelvis and ankles using a constrained Kalman filter (KF),assuming fixed body segment length, hinged knee joints, andperfect orientation measurements. It has short computationtime making it suitable for real-time applications [15].

C. Novelty

This paper describes a novel human pose estimator thatuses Lie group representation propagated iteratively using aconstrained EKF (CEKF) to estimate lower body kinematicsfor an RSC configuration of IMUs. Note that the frameworkis similar to [15]. The novelty is in the use of Lie grouprepresentation and the related formulation for an iterative in-ertial pose estimator with biomechanical constraints. The Liegroup representation used enables state propagation withoutleaving the Lie group space (i.e., without additional numeri-cal constraints) and represents uncertainty due to compoundnoise in position and orientation, rather than treating them asindependent noise processes, while an iterative estimator waschosen due to computation efficiency and suitability for real-time applications (e.g., gait assistive devices). The designwas motivated by the need to develop a gait assessment toolusing as few sensors as possible, ergonomically-placed forcomfort, to facilitate long-term monitoring of lower bodymovement.

II. ALGORITHM DESCRIPTION

The objective is to estimate the orientation of the pelvis,thighs, and shanks with respect the world frame, W , asdefined in Fig. 3. The proposed algorithm, i.e., the Lie groupCEKF (LG-CEKF), tracks the pose mean and error covari-ance of the pelvis and shanks in the world frame iteratively,while leveraging IMU measurements (i.e., acceleration andorientation) and assumptions each applied at different stages(i.e., prediction, measurement, and constraint updates) asshown in Fig. 1. The assumptions are i) the pelvis heightshould not drift far from the height at standing position; ii)the ankle is stationary and touches the floor during foot step;and iii) the lower body pose should satisfy biomechanicalconstraints (i.e.,, constant segment lengths, hinge knee joints,and knee angle within range of motion (ROM)). The errorcovariance was also bounded to prevent it from becomingbadly conditioned.

Similar implementations of the pre- and post-processingparts of [15] (except that orientation is now represented byrotation matrices instead of quaternions) are used and willonly be described briefly. Firstly, pre-processing involvesmeasuring/deriving the body segment orientation, inertialbody acceleration, and foot step events from the IMUs.Body segment orientation is obtained from a third-partyorientation estimation algorithm, then adjusted by a fixed 3Drotational offset aligning the sensor to the body frame basedon laboratory calibration data. Inertial body acceleration iscalculated by subtracting acceleration due to gravity frommeasured 3D acceleration in the world frame. Step events(i.e., foot contact with the ground) are detected using a third-party step detection algorithm. Secondly, post-processingcalculates the thigh orientations (which lack an IMU sensor)

from the model state tracked in the previous step using theequation, Rlt =

[rlsy × rltz rlsy rltz

](c.f. Fig. 3).

Fig. 1. Algorithm overview which consists of pre-processing, CEKF basedstate estimation, and post-processing. Pre-processing calculates the bodysegment orientation, inertial body acceleration, and step detection (fromraw acceleration), ak , angular velocity, ωk , and magnetic north heading,hk , measured by the IMU. The CEKF-based state estimation consists ofa prediction (kinematic equation), measurement (orientation, pelvis height,covariance limiter, intermittent zero-velocity update (when foot steps aredetected), and flat-floor assumption), and constraint update (thigh length,hinge knee joint, and knee range of motion). Post-processing calculates theorientation, Rk , of each lower body segments.

In the next subsection, a short introduction on Lie theory isgiven, followed by definition of chosen model and notations,and a detailed explanation of the algorithm.

A. Lie group and Lie algebra

The matrix Lie group G is a group of n×n matrices thatis also a smooth manifold (e.g., SE(3)). Group compositionand inversion (i.e., matrix multiplication and inversion) aresmooth operations. Lie algebra g represent a tangent spaceof a group at the identity element [16]. The elegance of Lietheory lies in being able to represent curve objects using avector space (e.g., Lie group G represented by g) [17].

The matrix exponential expG : g → G and matrixlogarithm logG : G → g establish a local diffeomorphismbetween the Lie group G its Lie algebra g. The Lie algebra gis a n×n matrix that can be represented compactly with ann dimensional vector space. A linear isomorphism betweeng and Rp is given by [ ]∨G : g→ Rp and [ ]∧G : Rp → g. Anillustration of the said mappings are given in Fig. 2.

Furthermore, the adjoint operators of a Lie group, denotedas AdG(X), and Lie algebra, denoted as adG(X) will beused in later sections. Also note [a]∧SE(3)b = [b]SE(3)a fora,b ∈ se(3) where the operator is as defined in [18, Eq.(72)]. For more detailed introduction of Lie groups includingthe adjoint operators, refer to [18, 19]. For an accessibleintroduction to Lie theory, refer to [17].

B. Physical model and mathematical notation

The model is represented by elements of the specialEuclidean group SE(3), representing the pelvis, thighs,and shanks (i.e., T = Tp,Tlt,Trt,Tls,Trs). DTC =

Lie group G

Lie algebra g

Rp

logG

expG

[ ]∨G

[ ]∧G

Fig. 2. Mapping between Lie group G, Lie algebra g, and a p-dimensionalvector space.

[DRC DpC

01×3 1

], DpC ∈ R3, DRC ∈ R3×3 denote the 4 × 4

transformation matrix, 3D position, and rotation matrix,respectively, of body segment C with respect to frameD. Note that the orientation representation used has nosingularity, and is comprised of basis vectors DrCx , DrCy ,and DrCz ∈ R3 (i.e., DRC =

[DrCx

DrCyDrCz

]). If frame

D is not specified, assume reference to the world frame, W .The system will be instrumented with an IMU at each of

the three locations: (1) the sacrum, approximately coincidentwith the mid-pelvis; (2 & 3) the left and the right shanks,just above the ankles, as shown in Fig. 3. The measuredacceleration and orientation of segment B are denoted asaBk and RB

k .

Fig. 3. Physical model of the lower body used by the algorithm. The circlesdenote joint positions, the solid lines denote instrumented body segments,whilst the dashed lines denote segments without IMUs attached (i.e., thighs).

C. System, measurement, and constraint models

The state estimator is based upon a Lie group CEKF,which combines a system model (Section II-D.1), a mea-surement model (Section II-D.2), and a kinematic constraintmodel (Section II-D.3). The estimator can be seen as trackingthe model states in matrix Lie group space, while trackingthe state error covariance in Lie algebra space. Here, wefirst introduce these system and measurement models beforepresenting the estimator.

Xk = Xk−1 expG([Ω(Xk−1) + nk−1]∧G) (1)Zk = h(Xk) expG ([mk]∧G) , Dk = c(Xk) (2)

where k is the time step; Xk ∈ G is the system state, anelement of state Lie group G; Ω (Xk) : G → Rp is a non-linear function; nk is a zero-mean process noise vector with

covariance matrix Qk (i.e., nk ∼ NRp(0p×1,Qk)); Zk ∈ G1

is the system measurement, an element of measurementLie group G1; h (Xk) : G → G1 is the measurementfunction; mk is a zero-mean measurement noise vector withcovariance matrix Rk (i.e., mk ∼ NRq (0p×1,Rk)); Dk ∈G2 is the constraint state, an element of constraint Lie groupG2; c (Xk) : G→ G2 is the equality constraint function thestate Xk must satisfy. Similar to [8, 20], the state distributionof Xk is assumed to be a concentrated Gaussian distributionon Lie groups (i.e., Xk = µk expG[ε]∧G where µk is themean of Xk and Lie algebra error ε ∼ NRp(0p×1,P))[21]. The Lie group and algebra state variables Xk and xk,respectively, model the position, orientation, and velocity ofthe three instrumented body segments as shown in Eqs. (3)and (4) (i.e., G = SE(3)3×R9) where τ =

[I3×3 τ01×3 1

]is the

trivial mapping of a 3D vector to an element in SE(3), and[ξB ]∧ is the Lie algebra of TB for some body segment B.[ ]∨, expG([ ]∧G), [logG( )]∨G, and Ad(Xk) are constructedsimilarly to Eq. (4).

Xk = diag(Tp,Tls,Trs, vp, vls, vrs

)(3)

[xk]∧ = diag([ξp]∧, [ξls]∧, [ξrs]∧, vp, vls, vrs

)(4)

D. Lie group constrained EKF (LG-CEKF)

The a priori (predicted), a posteriori (updated usingmeasurements), and constrained state (satisfying the stateconstraint equation, i.e., biomechanical constraints) for timestep k are denoted by µ−k , µ+

k , and µ+k , respectively. The

KF state error a priori and a posteriori covariance matricesare denoted as P−k and P+

k , respectively. The KF is basedon the Lie group EKF, as defined in [20]. Note that animplementation of this LG-CEKF algorithm will be madeavailable at: https://github.com/lsy3/lg-cekf.

1) Prediction step: estimates the kinematic state at thenext time step and may not necessarily respect the kinematicconstraints of the body, so joints may become dislocatedafter this prediction step. Below are the Lie EKF state andstate error covariance matrix propagation equations for theprediction step, as defined in [20].

µ−k+1 = µ+k expG([Ω+

k ]∧G) (5)

P−k+1 = FkP+k F

Tk + ΦG(Ωk)QkΦG(Ωk)T (6)

Fk = AdG(expG(−[Ωk]∧G)) + ΦG(Ωk)Ck (7)

Ck = ∂∂εΩ (µεk) |ε=0, ΦG(Xk) =

∞∑i=0

(−1)i

(i+1)!adG(Xk)i (8)

where Ω+k = Ω

(µ+k

)and µεk = µk expG([ε]∧G). The

specific definitions for LG-CEKF are as follows whereIi×j and 0i×j are i × j identity and zero matrices: ε =[(εpρ)

T (εpφ)T (εlsρ )T (εlsφ )T (εrsρ )T (εrsφ )T (εpv)T (εlsv )T (εrsv )T

]T,

Qk = diag(

∆t2

2 σmpacc, σmpqori,

∆t2

2 σlsacc, σlsqori,

∆t2

2 σrsacc,σrsqori, ∆t σmpacc, ∆t σlsacc, ∆t σrsacc

), ΦG(Xk) = diag(

ΦSE(3)(Tp), ΦSE(3)(T

ls), ΦSE(3)(Trs), I9×9).

Ω (Xk) =[ (

∆t vmpk + ∆t2

2 apk

)TRpk 01×3(

∆t vlak + ∆t2

2 alsk

)TRlsk 01×3(

∆t vrak + ∆t2

2 arsk

)TRrsk 01×3

∆t(ampk )T ∆t(alak )T ∆t(arak )T]T

(9)

Ck =

018×18

∆t(Rpk)T 03×3 03×3

03×3 03×3 03×3

03×3 ∆t(Rlsk )T 03×3

03×3 03×3 03×3

03×3 03×3 ∆t(Rrsk )T

03×3 03×3 03×3

018×27

(10)

2) Measurement update: estimates the state at the nexttime step by: (i) updating the orientation state using new ori-entation measurements of body segments, (ii) enforcing softpelvis position constraints based on initial pelvis height, andby; (iii) utilizing zero ankle velocity and flat floor assump-tions whenever a footstep is detected. For the covarianceupdate, there is an additional step to limit the a posterioricovariance matrix elements from growing indefinitely andfrom becoming badly conditioned. The a posteriori state µ+

k

is calculated following the Lie EKF equations below, whereRk = diag(σk). See [20] for more details.

Kk = P−kHTk

(HkP−kH

Tk + Rk

)−1(11)

νk = Kk

([logG1

(h(µ−k )−1Zk

)]∨G1

)(12)

Hk = ∂∂ε [logG1

(h(u−k)−1

h (µεk))]∨G1|ε=0 (13)

µ+k = µ−k expG ([νk]∧G) (14)

Hk varies with time depending on floor contact (FC)as shown in Eq. (15). Hori, Hmp, Hls, and Hrs will bedescribed below. The derivation of these equations is theproduce of tedious algebraic manipulation and first orderlinearization (i.e., exp([φ]∧) ≈ I + [φ]∧). Measurementvariance σk is constructed similarly to Eq. (15). Zk andh (Xk) are constructed similarly to Eq. (15) but com-bined using diag instead of concatenation (e.g., h (Xk) =diag(hmp (Xk) , hla (Xk))).

Hk =

[HTori HTmp]T no FC[HTori HTmp HTls]T left FC[HTori HTmp HTrs]T right FC[HTori HTmp HTls HTrs]T both FC

(15)

Let us define, ix, iy , iz , and i0 as 4×1 vectors whose 1st

to 4th row, respectively, are 1, while the rest are 0. Firstly,the orientation update is implemented by Zori and Hori asshown in Eqs. (17) and (18) with measurement noise varianceσ2ori (9 × 1 vector). Secondly, the soft mid-pelvis position

constraint encourages the pelvis z position to be close tothe initial pelvis z position at time k = 0 (i.e., standing

height zp), and is implemented by Zmp and Hmp as shownin Eqs. (19) and (20), with measurement noise variance σ2

mp

(1×1 vector). Thirdly, if a left step is detected, the left anklevelocity is encouraged to approach zero, and the left ankle zposition to be close to the floor level, zf . These assumptionsare implemented by Zls and Hls as shown in Eqs. (21) and(22) with measurement noise variance σ2

ls (4 × 1 vector).Zrs and Hrs can be constructed similarly.

hori (Xk) = diag(Rpk,R

lsk ,R

rsk ) (16)

Zori = diag(Rpk, R

lsk , R

rsk ) (17)

Hori =

03×3 I3×3

03×3 I3×3 09×9

03×3 I3×3

(18)

hmp (Xk) = iTz Tpi0, Zmp = zp (19)Hmp =

[iTz Tp[i0] 01×6 01×6 01×9

](20)

hls (Xk) =

[vls

iTz Tlsi0

], Zls =

[03×1

zf

](21)

Hls =

. . . pos. ori. col.. . .

I3×3︸︷︷︸ . . .︷ ︸︸ ︷iTz Tls[i0] vel. col.

(22)

Lastly, the covariance limiter prevents the covariance fromgrowing indefinitely and from becoming badly conditioned,as will happen naturally when tracking the global position ofthe pelvis and ankles without any global position reference.At this step, a pseudo-measurement equal to the current stateµ+k is used (implemented by Hlim =

[I18×18 018×9

]) with

some measurement noise of variance σlim (9×1 vector). Thecovariance P+

k is then calculated through Eqs. (23)-(25).

H′k =[HTk HTlim

]T, R′k = diag([σk σlim]) (23)

K′k = P−kH′Tk

(H′kP−kH

′Tk + R′

)−1(24)

P+k = ΦG(νk) (I−K′kH′k) P−k ΦG(νk)T (25)

3) Satisfying biomechanical constraints: After the pre-diction and measurement updates of the EKF, above, thebody joints may have become dislocated, or joint anglesextend beyond their allowed range. This update correctsthe kinematic state estimates to satisfy the biomechanicalconstraints of the human body by projecting the currenta posteriori state µ+

k estimate onto the constraint surface,guided by our uncertainty in each state variable, encodedby P+

k . The constraint equations enforce the followingbiomechanical limitations: (i) the length of estimated thighvectors (|| τ lt|| and || τ rt||) equal the thigh lengths dlt anddrt; (ii) both knees act as hinge joints; and (iii) the knee jointangle is confined to realistic ROM. The constrained state µ+

k

can be calculated using the equations below, similar to themeasurement update of [20] with zero noise:

Kk = P+k C

Tk

(CkP+

k CTk

)−1(26)

νk = Kk

([logG2

(c(µ+

k )−1Dk

)]∨G2

)(27)

Ck = ∂∂ε [logG2

(c(u+k

)−1c (µεk)

)]∨G2|ε=0 (28)

µ+k = µ+

k expG ([νk]∧G) (29)

where Ck =[CTL,k CTR,k

]T. CL,k is shown in Eq. (30) where

a bounded knee angle, αlk, is defined as αlk,min < αlk <αlk,max . The constraints for the left leg, CL,k, will bedescribed below. The derivation of these equations is theproduce of tedious algebraic manipulation and first orderlinearization (e.g., exp([φ]∧) ≈ I+[φ]∧). CR,k can be derivedsimilarly.

CL,k =

[CTltl,k CTlkh,k]T bounded αlk,[CTltl,k CTlkh,k CTlkr,k]T otherwise.

(30)

Firstly, the constraint for the length of the estimated thighvector is shown in Eq. (33). The thigh vector, τ ltz (µ+

k ), asshown in Eq. (32) was obtained by subtracting the knee jointposition from hip joint position.

pplh =[0 dp

2 0 1]T, lsplk =

[0 0 dls 1

]T(31)

τ ltz (µ+k ) =

E︷ ︸︸ ︷[I3×3 03×1

] ( hip joint pos.︷ ︸︸ ︷Tp pplh −

knee joint pos.︷ ︸︸ ︷Tls lsplk

)(32)

cltl(µ+k ) = τ ltz (µ+

k )T τ ltz (µ+k )− (dlt)2 = 0 = Dltl (33)

Γ1 =(Tp pplh − Tls lsplk

)TETE (34)

Cltl =[2Γ1 Tp[pplh] − 2Γ1 Tls[lsplk] 01×15

](35)

Secondly, the constraint for the hinge knee joint enforcesthe long (z) axis of the thigh to be perpendicular to themediolateral axis (y) of the shank, as shown in Eq. (36).This formulation is similar to [22, Sec. 2.3 Eqs. (4)].

clkh(µ+k ) = (rlsy )T τ ltz = 0 = Dlkh (36)

Γ2 = (rlsy )TE = (E Tlsiy)TE (37)

Clkh =[Γ2 Tp[pplh] Γ1 Tls[iy]–Γ2 Tls[lsplk] 01×15

](38)

Thirdly, the constraint for the knee ROM is enforced if theknee angle is outside the allowed ROM. This implementationis similar to the active set method used in optimization. Math-ematically, this is implemented by setting the constrainedknee angle α′lk to Eq. (39) where αlk,min = 0 to preventknee hyperextension and αlk,max = min(180, α+

lk). Theknee angle αlk is calculated by taking the inverse tangent ofthe thigh vector, rltz , projected on the z and x axes of theshank orientation as shown in Eq. (40). It ranges from −π2 to3π2 as enforced by the chosen sign inside the tangent inverse

function and the addition of π2 .

α′lk = min(αlk,max,max(αlk,min, αlk)) (39)

αlk = tan−1(−(rlsz )T rltz−(rlsx )T rltz

)+ π

2 (40)

−(rlsz )T rltz−(rlsx )T rltz

=sin(α′lk−

π2 )

cos(α′lk−π2 )

(41)

clkr(µ+k ) = ((rlsz )T cos(α′lk–

π2 )–(rlsx )T sin(α′lk–

π2 )) rltz

= (E Tlsψ)T τ ltz = 0 = Dlkr

(42)

ψ = iz cos(α′lk–π2 )–ix sin(α′lk–

π2 ), Γ3 = (E Tlsψ)TE (43)

Clkr =[Γ3 Tp[pplh] Γ1 Tls[ψ]–Γ3 Tls[lsplk] 01×15

](44)

III. EXPERIMENT

The goal of the experiment is to evaluate the algorithmdescribed in this paper against benchmark systems, focusingonly on the kinematics of the pelvis, thighs, and shanks.

A. Setup

The algorithm was tested on the walking data set of [15],and on additional dynamic movements as listed in Table I.The experiment used nine healthy volunteers (7 men and 2women, weight 63.0 ± 6.8 kg, height 1.70 ± 0.06 m, age24.6 ± 3.9 years old), and utilized two benchmark systems(Vicon and Xsens). The setup of each of these systems wasidentical to [15, Sec. III] where both sampling rates were100 Hz, and the recordings were synchronized by havingthe Xsens Awinda station send a trigger pulse to the Viconsystem at the start and end event for each recording.

Each subject performed two trials of the movements listedin Table I. The experiment was approved by the HumanResearch Ethics Committee of the University of New SouthWales with approval number HC180413.

TABLE ITYPES OF MOVEMENTS DONE IN THE VALIDATION EXPERIMENT

Movement Description Duration (s)Walk Walk straight and return ∼ 30Figure-of-eight Walk along figure-of-eight path ∼ 60Zig-zag Walk along zig-zag path ∼ 605-minute walk Unscripted walk, side step, and stand ∼ 300Speedskater Speedskater on the spot ∼ 30Jog Jog straight and return ∼ 30Jumping jacks Jumping jacks on the spot ∼ 30High knee High knee jog straight and return ∼ 30

B. System parameters

Comparison was done in the world frame, W , which wasset equal to the Xsens frame. A fixed yaw offset was appliedto compensate for varying magnetic interference betweenIMUs and align the x axes (north) of all sensors. Themeasured orientation, Rp

k, Rlsk , R

rsk , were obtained from the

black-box orientation estimation algorithm provided by theXsens system [1], while the 3D rotational offset from thesensor to body frame was obtained from the initial posemeasured by the Vicon system at standing position (i.e.,N pose). A step is detected if the variance of the freebody acceleration across the 0.25 second window is below1 m.s−2. The step events were also manually reviewed andcorrected to remove false positives. Refer to [15, Sec. III-B and C] for details. The algorithm and calculations wereimplemented using Matlab 2018b.

The initial position, orientation, and velocity (µ+0 ) were

obtained from the Vicon benchmark system. P+0 was set

to 0.5I27×27. The variance parameters used to generate theprocess and measurement error covariance matrix Q and Rare shown in Table II.

TABLE IIVARIANCE PARAMETERS FOR GENERATING THE PROCESS AND

MEASUREMENT ERROR COVARIANCE MATRICES, Q AND R.

Q Parameters R Parametersσ2

acc σ2wori

σ2ω σ2

mp σ2ls and σ2

rs σ2lim

(m2.s−4) (rad2.s−2) (m2) (m2.s−2 and m2) (m2)10219 103112 0 1 [0.0113 10−4] 10118

where 1n is an 1× n row vector with all elements equal to 1.

C. Evaluation MetricsThe following metrics were used to benchmark the algo-

rithm’s accuracy. Note that ˜ indicates estimated parameter.Refer to [15, Sec. III-D] for details.

1) Mean position RMSE: epos as shown in Eq. (45) isa common metric in vision-based human motion capturesystems (e.g., [14]) to measure position accuracy. Note thatthe mid-pelvis is the origin for all RMSE calculations.

2) Mean orientation RMSE: eori as shown in Eq. (46) arethe exponential coordinates of the rotational offset betweenthe estimated and benchmark orientation of the thighs.

3) Coefficient of correlation (CC): of hip joint anglesin the Y, X, and Z plane and knee joint angle in the Yplane are useful indicators of the system accuracy for clinicalapplications. The CC of joint i is obtained using Eq. (47).

epos,k = 1Npos

∑i∈joints || pik − pik|| (45)

eori,k = 1Nori

∑i∈thighs ||[Ri

k(Rik)T ]∨|| (46)

CCi =n∑θik θ

ik−(

∑θik)(

∑θik)√

n(∑

(θik)2)−(∑θik)

2√n(

∑(θik)2)−(

∑θik)

2(47)

IV. RESULTS

A. Mean position and orientation RMSEFig. 4 shows the mean position and orientation RMSE

of our algorithm for each movement type compared againstthe Vicon output. For brevity, the results of Walk, Figure-of-eight, Zig-zag, and 5-minute walk are summarized underFree walk. The comparison involved the output from fourconfigurations of interest, all compared against the Vicongold standard output: i) our algorithm taking as input theacceleration (double derivative of position) and orientationobtained from Vicon (denoted as LGKF-Vicon), which givesinsight into the algorithm’s performance when given inputswhich corresponds perfectly with the benchmark system; ii)the black box output from Xsens MVN Studio software, acommercial IMC (denoted as OSPS). iii) constrained KF(CKF) from [15] (denoted as CKF-3IMU), and; iv) ouralgorithm using acceleration and orientation obtained fromXsens MTx IMU measurements (denoted as LGKF-3IMU).

B. Hip and knee joint angle CCFig. 5 shows the knee (Y) and hip (Y, X, Z) joint angle

CC for LGKF-3IMU and CKF-3IMU compared against theVicon output. Note that Y, X, and Z refers to the planedefined by the normal vectors y, x, and z axes, and arealso known as the sagittal, frontal, and transversal plane,respectively, in the context of gait analysis. Fig. 6 shows asample output for a Walk trial.

Fig. 4. The mean position and orientation RMSE, epos (top) and eori(bottom), of each motion type.

Fig. 5. The CC of knee (Y) and hip (Y, X, Z) joint angles for LGKF-3IMU(prefix LG) and CKF-3IMU (prefix C) at each motion type.

V. DISCUSSION

In this paper, an LG-CEKF algorithm for lower body poseestimation using only three IMUs, ergonomically placed onthe ankles and sacrum to facilitate continuous recording out-side the laboratory, was described and evaluated. It utilizesa Lie group/algebra representation in an iterative estimator.While using few sensors than a OSPS system, it achievescomparable accuracy.

A. Mean position and orientation RMSE comparison

The mean position and orientation RMSE, epos and eori,of LGKF-Vicon, LGKF-3IMU, OSPS, and related literaturefor all motions are shown in Table III [14, 15]. The eposand eori difference between LGKF-Vicon and LGKF-3IMUwere around 2 cm and 4, respectively. This result shows thatLG-CEKF was able to handle sensor noise from raw IMUmeasurements. Note that the relatively large epos and eori of

Fig. 6. Knee (Y) and hip (Y, X, Z) joint angle output of CKF-3IMU incomparison with the benchmark system (Vicon) for a Walk trial. The subjectwalked straight from t = 0 to 3 s, turned 180 around from t = 3 to 5.5s, and walked straight to the original starting point from 5.5 s until the endof the trial.

LGKF-Vicon was due to the constant body segment lengthand hinge knee joint assumption which does not necessarilyhold for the Vicon system estimates. The error was consistentwith CKF-Vicon from [15], and was even worse for dynamicmovements where kinematic assumptions are violated toa greater extent. The OSPS errors were consistent for allmovements. Although the epos and eori difference betweenLGKF-Vicon, LGKF-3IMU, and OSPS for Free walk werecomparable, the OSPS error for the other movements weresignificantly smaller which again demonstrates the differ-ences caused by our constraint assumptions. Note that therelatively large epos and eori of OSPS may be the resultof differences in the calibration processes for the Xsens andVicon systems [23]. If constant bias error is removed, as wasdone in [23], we expect both LGKF-3 and OSPS to improve.

LGKF-3IMU was compared to CKF-3IMU [15], and totwo algorithms from the study of Marcard et al. [14]; namely,sparse orientation poser (SOP) and sparse inertial poser(SIP). All algorithms utilized information from a commonsensor system (i.e., Xsens). SOP only utilized orientationinformation, while the rest utilized both orientation andacceleration information from IMUs. Note that SOP and SIPwere compared against the Xsens system, and the othersagainst the Vicon system. As can be observed in Fig. 4,the epos and eori difference between LGKF-3IMU and CKF-3IMU for Free walk and Speedskater movement were similar,while there were significant improvements for Jog, Jumpingjacks, and High knee jog movements. As can be observed inTable III, the epos and eori difference between LGKF-3IMUand SOP were ~2 cm and ~2 (i.e., similar). However, theepos and eori of SIP were smaller than LGKF-3IMU by ~4cm and ~8, respectively, maybe because SIP optimizes thepose over multiple frames whereas LGKF-3IMU optimizesthe pose for each individual frame.

Comparing processing times, LG-CEKF was approxi-mately three times slower than CKF but is still dramaticallyfaster than SIP; LG-CEKF and CKF processed a 1,000-framesequence in ~2 and ~0.7 seconds, respectively, on an IntelCore i5-6500 3.2 GHz CPU, while SIP took 7.5 minutes ona quad-core Intel Core i7 3.5 GHz CPU. All set-ups usedsingle-core non-optimized Matlab code [14, 15].

B. Hip and knee joint angle CC comparison

The knee and hip joint angle CCs of LGKG-3IMU inthe sagittal plane for Free walk (0.88 and 0.77) indicategood correlation with the Vicon benchmark system. TheCCs for the remaining movements were not as good. How-ever, there was significant improvement over CKF-3IMU forSpeedskater, Jog, and High knee jog trials. Both CCs ofLGKF-3IMU and CKF-3IMU were smaller in the frontal andtransverse plane, which is common amongst OSPS systemswhen compared against optical motion capture systems (e.g.,Vicon) [23].

C. Improvements and similarities to CKF

LGKF-3IMU was able to achieve comparable and occa-sionally better results than CKF-3IMU using fewer assump-

TABLE IIIMEAN POSITION AND ORIENTATION RMSE OF LGKF-Vicon AND

LGKF-3IMU, CKF-3IMU, SPARSE ORIENTATION AND INERTIAL POSER

(SOP AND SIP) [14]

Free walk LGKF-Vicon LGKF-3IMU CKF-3IMU SOP SIP

epos (cm) 4.65± 0.98 5.75± 1.39 5.21± 1.30 ~5.00 ~3.00eori () 14.9± 3.3 19.8± 5.2 18.9± 5.3 ~15.0 ~11.0

Jog LGKF-Vicon LGKF-3IMU CKF-3IMU SOP SIP

epos (cm) 7.32± 1.74 8.36± 1.61 11.39± 1.50 ~8.00 ~5.00eori () 20.7± 3.4 23.4± 5.1 29.4± 4.7 ~22.0 ~15.0

JumpingLGKF-Vicon LGKF-3IMU CKF-3IMU SOP SIPjacks

epos (cm) 6.35± 1.24 8.35± 1.53 10.65± 2.94 ~8.00 ~4.00eori () 20.6± 4.0 22.7± 5.1 26.7± 7.1 ~20.0 ~12.0

tions (i.e., encourage pelvis x and y position to approachthe average of the left and right ankle x and y positionsduring the measurement update, and the prevention of kneeangle decrease during the constraint update [15, Sec. II-E.2and 3]). Furthermore, LGKF-3IMU does not assume perfectorientation during the constraint update, in contrast to CKF-3IMU, which can be beneficial if new sensor informationthat informs segment orientation is added.

Similar to CKF-3IMU, LGKF-3IMU requires the covari-ance limiter (Sec. II-D.2) to prevent the covariance matrixfrom becoming badly conditioned over longer durations 5-minute walk. LGKF-3IMU also have similar limitations andpotentials during longer-term tracking of activities of dailyliving, being unable to handle the activities of sitting, lyingdown, or climbing stairs due to the pelvis height and/or flatfloor assumptions. It is also unable to track people withvarus or valgus deformity, or those capable of hyperextendingthe knee due to the algorithm’s hinge knee joint and ROMconstraints. However, the good hip and knee joint angle CCsin the sagittal plane indicate potential clinical application forpathologies concerned with these gait parameters.

VI. CONCLUSION

This paper presented a Lie group CEKF-based algorithmto estimate lower limb kinematics using a reduced sensorcount configuration, and without using any reference motiondatabase. The mean position and orientation RMSEs (relativeto the mid-pelvis origin) for Walk movements were 5.75±1.4cm and 19.8± 5.2, respectively. The Y plane knee and hipangle CCs were 0.88±0.1 and 0.77±0.1. To improve perfor-mance, additional information relating the pelvis and anklekinematics is needed (e.g., utilize sensors that give pelvisdistance or position relative to the ankle). The source codefor the LG-CEKF algorithm and a sample video will be madeavailable at https://github.com/lsy3/lg-cekf.

ACKNOWLEDGEMENT

This research was supported by an Australian GovernmentResearch Training Program (RTP) Scholarship.

REFERENCES

[1] D. Roetenberg, H. Luinge, and P. Slycke, “Xsens MVN: Full 6DOFhuman motion tracking using miniature inertial sensors,” XsensMotion Technol. BV, Tech. Rep, vol. 1, 2009.

[2] BioSenics, LEGSys, 2018.[3] M. B. Del Rosario, N. H. Lovell, and S. J. Redmond, “Quaternion-

based complementary filter for attitude determination of a smart-phone,” IEEE Sens. J., vol. 16, no. 15, pp. 6008–6017, 2016.

[4] M. B. Del Rosario, P. Ngo, H. Khamis, N. H. Lovell, S. J. Redmond,P. Ngo, N. H. Lovell, and S. J. Redmond, “Computationally EfficientAdaptive Error-State Kalman Filter for Attitude Estimation,” IEEESens. J., vol. 18, no. 22, pp. 9332–9342, 2018.

[5] P. B. Shull, W. Jirattigalachote, M. A. Hunt, M. R. Cutkosky, andS. L. Delp, “Quantified self and human movement: A review on theclinical impact of wearable sensing and feedback for gait analysisand intervention,” Gait Posture, vol. 40, no. 1, pp. 11–19, 2014.

[6] R. Lloréns, J. A. Gil-Gómez, M. Alcañiz, C. Colomer, and E.Noé, “Improvement in balance using a virtual reality-based steppingexercise: A randomized controlled trial involving individuals withchronic stroke,” Clin. Rehabil., vol. 29, no. 3, pp. 261–268, 2015.

[7] P. Shull, K. Lurie, M. Shin, T. Besier, and M. Cutkosky, “Haptic gaitretraining for knee osteoarthritis treatment,” in 2010 IEEE HapticsSymp., IEEE, 2010, pp. 409–416.

[8] J. Cesic, V. Joukov, I. Petrovic, and D. Kulic, “Full body humanmotion estimation on lie groups using 3D marker position measure-ments,” IEEE-RAS Int. Conf. Humanoid Robot., pp. 826–833, 2016.

[9] G. Bourmaud, R. Mégret, M. Arnaudon, and A. Giremus,“Continuous-Discrete Extended Kalman Filter on Matrix Lie GroupsUsing Concentrated Gaussian Distributions,” J. Math. Imaging Vis.,vol. 51, no. 1, pp. 209–228, 2014.

[10] M. Brossard, S. Bonnabel, and J. P. Condomines, “UnscentedKalman filtering on Lie groups,” in IEEE Int. Conf. Intell. Robot.Syst., vol. 2017-Septe, 2017, pp. 2485–2491.

[11] R. Vemulapalli, F. Arrate, and R. Chellappa, “Human action recog-nition by representing 3D skeletons as points in a lie group,”Proc. IEEE Comput. Soc. Conf. Comput. Vis. Pattern Recognit.,pp. 588–595, 2014.

[12] T. D. Barfoot and P. T. Furgale, “Associating uncertainty with three-dimensional poses for use in estimation problems,” IEEE Trans.Robot., vol. 30, no. 3, pp. 679–693, 2014.

[13] X. Hu, C. Yao, and G. S. Soh, “Performance evaluation of lowerlimb ambulatory measurement using reduced Inertial MeasurementUnits and 3R gait model,” in IEEE Int. Conf. Rehabil. Robot., 2015,pp. 549–554.

[14] T. von Marcard, B. Rosenhahn, M. J. Black, and G. Pons-Moll,“Sparse inertial poser: Automatic 3d human pose estimation fromsparse IMUs,” in Comput. Graph. Forum, Wiley Online Library,vol. 36, 2017, pp. 349–360. arXiv: 1703.08014.

[15] L. Sy, M. Raitor, M. B. Del Rosario, H. Khamis, L. Kark, Nigel HLovell, and S. J. Redmond, “Estimating lower limb kinematics usinga reduced wearable sensor count,” Submitted and under review.

[16] J. M. Selig, “Lie groups and lie algebras in robotics,” in Comput.Noncommutative Algebr. Appl. Springer, 2004, pp. 101–125.

[17] J. Stillwell, Naive lie theory. Springer Science & Business Media,2008.

[18] T. D. Barfoot, State Estimation for Robotics. Cambridge UniversityPress, 2017.

[19] G. Chirikjian, Stochastic models, information theory, and Lie groups.II: Analytic methods and modern applications. 2012.

[20] G. Bourmaud, A. Giremus, Y. Berthoumieu, and G. Bourmaud,“Discrete extended Kalman filter on lie groups,” pp. 1–5, 2013.

[21] Y. Wang and G. S. Chirikjian, “Error propagation on the Euclideangroup with applications to manipulator kinematics,” IEEE Trans.Robot., vol. 22, no. 4, pp. 591–602, 2006.

[22] X. L. Meng, Z. Q. Zhang, S. Y. Sun, J. K. Wu, and W. C.Wong, “Biomechanical model-based displacement estimation inmicro-sensor motion capture,” Meas. Sci. Technol., vol. 23, no. 5,p. 055 101, 2012.

[23] T. Cloete and C. Scheffer, “Benchmarking of a full-body inertialmotion capture system for clinical gait analysis,” in 2008 30th Annu.Int. Conf. IEEE Eng. Med. Biol. Soc., IEEE, 2008, pp. 4579–4582.