Real-Time Reactive Trip Avoidance for Powered Transfemoral...

9
Real-time Reactive Trip Avoidance for Powered Transfemoral Prostheses Nitish Thatte , Nandagopal Srinivasan , and Hartmut Geyer Robotics Institute, Mechanical Engineering Carnegie Mellon University, Pittsburgh, Pennsylvania 15213 Email: [email protected], [email protected], [email protected] Abstract—This paper presents a real-time reactive controller for a powered prosthesis that addresses the problem of trip avoidance. The control estimates the pose of the leg during swing with an extended Kalman filter, predicts future hip angles and hip heights using sparse Gaussian Processes, and reactively plans updated ankle and knee trajectories with a fast quadratic program solver to avoid trips. In preliminary experiments with an able-bodied user who purposefully lowered the hip to elicit trips on each swing, the proposed control reduced the rate of tripping by 68% when compared to a swing control that follows standard minimum- jerk trajectories. In addition, the proposed control also reduced the severity of toe-scung. To the best of our knowledge, this controller is the first to incorporate visual feedback in the real- time planning and control of a lower limb prosthesis during gait. The results demonstrate the potential of reactive and environment- aware controls to improve amputee gait robustness and encourage future development of leg prosthesis controls that can react in real-time to the environment and user state. I. I Lower limb amputees using state-of-the-art commercial prostheses face a number of gait deficiencies that negatively impact their quality of life [6]. Of acute significance among these deficiencies are the increased risk of falling and the related injuries, which can lead to amputees avoiding activity out of a fear falling [16]. As falls and their avoidance are linked to swing leg placement in locomotion, active swing control strategies could help to substantially reduce the risk of falling. However, current swing controllers of transfemoral prostheses do little to proactively minimize this risk. Existing swing phase control approaches for powered prosthe- ses predominantly seek to reproduce the average swing phase behavior of the human leg. Whether the approach is based on trajectory planning [12], impedance control [24], or phase- based control [18], they all treat the swing phase motion as an “open loop” problem with respect to trip hazards, as none of the approaches take the location of the heel and toe of the prosthetic foot with respect to the ground explicitly into account. Therefore, current swing control strategies neglect a clear advantage that robotic prostheses can have over their passive counterparts: the ability to sense and act upon environmental information. In this work, we develop a swing control strategy to reactively avoid trips with powered transfemoral prostheses that uses visual information about the environment and an estimate of the prosthesis configuration. Some previous studies have explored incorporating visual feedback into the control of leg prostheses. For example, Scandaroli et al. [21] developed a state estimator and controller that allowed the ankle joint of a prosthesis to conform to the slope of the ground under the foot. To address the problem of terrain recognition, Zhang et al. [27] developed a classifier using a LIDAR and an IMU to discriminate between terrains such as flat ground and steps. More recently, Liu et al. [13] combined this terrain classifier with a Bayesian intent classifier (based on [3]) to develop an environment-aware locomotion mode recognition system. In addition, RGBD sensors have been explored as a source of rich environmental information for legged assistance, including gait recognition [15] and stair detection [4, 10]. However, none of these previous studies have implemented a control strategy that uses information about the state of the prosthesis with respect to its environment to reactively govern the motion of a powered prosthesis in real-time. Hayashi and Kiguchi [8] do propose such a control strategy for a powered exoskeleton that assists with obstacle avoidance. This work used a terrain map generated by a scanning LIDAR and sensors on both the stance and swing legs to provide assistive torques that prevent trips. Here, we present an approach for real-time, reactive trip- avoidance control of a powered prosthesis that does not require stance leg sensing and uses a simple 1-D LIDAR distance sensor. The approach combines three building blocks. First, we use an extended Kalman filter (EKF) that fuses measurements from an IMU, a 1-D LIDAR, and the prosthesis’ encoders to estimate the current pose of the prosthetic leg with respect to the ground. Second, during swing we predict likely future leg trajectories with sparse Gaussian process models. Finally, we use the leg pose estimate and trajectory predictions in a fast quadratic-program planner to reactively generate in real time leg joint trajectories that avoid premature toe and heel contact with the ground. To evaluate the proposed control, we compare our method for trip avoidance to a standard non-reactive minimum-jerk trajectory planning approach in a prosthesis walking experiment designed to elicit trips. II. M The trip avoidance control we propose involves (1) estimating the position and orientation of the leg (section II-A), (2) predicting the future hip angles and heights (section II-B), and (3) planning corresponding knee and ankle trajectories such that the heel and toe will not contact the ground prematurely (section II-C).

Transcript of Real-Time Reactive Trip Avoidance for Powered Transfemoral...

Page 1: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

Real-time Reactive Trip Avoidance for PoweredTransfemoral Prostheses

Nitish Thatte⇤, Nandagopal Srinivasan†, and Hartmut Geyer⇤⇤Robotics Institute, †Mechanical Engineering

Carnegie Mellon University, Pittsburgh, Pennsylvania 15213Email: [email protected], [email protected], [email protected]

Abstract—This paper presents a real-time reactive controller fora powered prosthesis that addresses the problem of trip avoidance.The control estimates the pose of the leg during swing with anextended Kalman filter, predicts future hip angles and hip heightsusing sparse Gaussian Processes, and reactively plans updatedankle and knee trajectories with a fast quadratic program solverto avoid trips. In preliminary experiments with an able-bodieduser who purposefully lowered the hip to elicit trips on eachswing, the proposed control reduced the rate of tripping by 68%when compared to a swing control that follows standard minimum-jerk trajectories. In addition, the proposed control also reducedthe severity of toe-scu�ng. To the best of our knowledge, thiscontroller is the first to incorporate visual feedback in the real-time planning and control of a lower limb prosthesis during gait.The results demonstrate the potential of reactive and environment-aware controls to improve amputee gait robustness and encouragefuture development of leg prosthesis controls that can react inreal-time to the environment and user state.

I. I�����������Lower limb amputees using state-of-the-art commercial

prostheses face a number of gait deficiencies that negativelyimpact their quality of life [6]. Of acute significance amongthese deficiencies are the increased risk of falling and the relatedinjuries, which can lead to amputees avoiding activity out of afear falling [16]. As falls and their avoidance are linked to swingleg placement in locomotion, active swing control strategiescould help to substantially reduce the risk of falling. However,current swing controllers of transfemoral prostheses do little toproactively minimize this risk.

Existing swing phase control approaches for powered prosthe-ses predominantly seek to reproduce the average swing phasebehavior of the human leg. Whether the approach is basedon trajectory planning [12], impedance control [24], or phase-based control [18], they all treat the swing phase motion as an“open loop” problem with respect to trip hazards, as none of theapproaches take the location of the heel and toe of the prostheticfoot with respect to the ground explicitly into account. Therefore,current swing control strategies neglect a clear advantage thatrobotic prostheses can have over their passive counterparts: theability to sense and act upon environmental information.

In this work, we develop a swing control strategy to reactivelyavoid trips with powered transfemoral prostheses that usesvisual information about the environment and an estimate of theprosthesis configuration. Some previous studies have exploredincorporating visual feedback into the control of leg prostheses.For example, Scandaroli et al. [21] developed a state estimator

and controller that allowed the ankle joint of a prosthesis toconform to the slope of the ground under the foot. To addressthe problem of terrain recognition, Zhang et al. [27] developeda classifier using a LIDAR and an IMU to discriminate betweenterrains such as flat ground and steps. More recently, Liuet al. [13] combined this terrain classifier with a Bayesianintent classifier (based on [3]) to develop an environment-awarelocomotion mode recognition system. In addition, RGBD sensorshave been explored as a source of rich environmental informationfor legged assistance, including gait recognition [15] and stairdetection [4, 10]. However, none of these previous studies haveimplemented a control strategy that uses information aboutthe state of the prosthesis with respect to its environment toreactively govern the motion of a powered prosthesis in real-time.Hayashi and Kiguchi [8] do propose such a control strategy fora powered exoskeleton that assists with obstacle avoidance. Thiswork used a terrain map generated by a scanning LIDAR andsensors on both the stance and swing legs to provide assistivetorques that prevent trips.

Here, we present an approach for real-time, reactive trip-avoidance control of a powered prosthesis that does not requirestance leg sensing and uses a simple 1-D LIDAR distancesensor. The approach combines three building blocks. First, weuse an extended Kalman filter (EKF) that fuses measurementsfrom an IMU, a 1-D LIDAR, and the prosthesis’ encoders toestimate the current pose of the prosthetic leg with respectto the ground. Second, during swing we predict likely futureleg trajectories with sparse Gaussian process models. Finally,we use the leg pose estimate and trajectory predictions in afast quadratic-program planner to reactively generate in realtime leg joint trajectories that avoid premature toe and heelcontact with the ground. To evaluate the proposed control, wecompare our method for trip avoidance to a standard non-reactiveminimum-jerk trajectory planning approach in a prosthesiswalking experiment designed to elicit trips.

II. M������

The trip avoidance control we propose involves (1) estimatingthe position and orientation of the leg (section II-A), (2)predicting the future hip angles and heights (section II-B), and(3) planning corresponding knee and ankle trajectories suchthat the heel and toe will not contact the ground prematurely(section II-C).

Page 2: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

O T

LA

K

H

Lid0

I

Lidf

Fig. 1: Kinematic model of the user and prosthesis used for stateestimation and motion planning. The model includes the hip (H),knee (K), ankle (A), heel (L) and toe points (T). Additionally,the start (Lid0) and end (Lidf ) points of the LIDAR beam (withlength `) are indicated. The IMU is located at point I. Boththe LIDAR and IMU are mounted to the thigh portion of thepowered knee-and-ankle prosthesis.

A. Extended Kalman Filter for estimating LegPosition/Orientation

To estimate the position and orientation of the leg, we employan EKF that fuses information from a LIDAR distance sensor(SICK OD1000), an IMU (YEI Technologies 3-Space sensor),and encoders on the prosthesis (Renishaw Resolute, Netzer DS-25). The EKF filters the nonlinear, discrete-time dynamics givenby

xt =266664qtpt€pt

377775=

266664fgyro(!t ) 0 0

0 I3⇥3 �t I3⇥30 0 I3⇥3

377775xt�1

+

2666640

12�t2I3⇥3�t I3⇥3

377775266664ROI(qt�1)at �

26666400g

377775377775+ wt (1)

= f (xt�1, ut ) + wt,

where q is the quaternion orientation, ROI and p are the rotationmatrix and position of the IMU in inertial coordinates, ! is thebias-corrected angular rate measured by the gyroscope, fgyrointegrates the gyroscope rate to update the orientation (formore details see [14]), a is the accelerometer measurement,ut = [!t, at ]T , and �t is the integration time step (1 ms).

The dynamics are corrupted by process noise wt ⇠ N(0,Qt )due to the inaccuracy of the IMU’s measurement of the trueacceleration and angular velocity. Consequently, Qt is given by

Qt =@ f@u

����xt�1,ut

�2! I3⇥3 0

0 �2a

I3⇥3

�@ f@u

����T

xt�1,ut

, (2)

where �2! and �2

aare the gyroscope and accelerometer mea-

surement variances, respectively.To estimate the pose given our sensor measurements, we

follow a standard EKF procedure [1], reviewed here for com-pleteness. The EKF state estimation process has two steps: First,we predict the next state distribution by forward-propagatingthe mean x̂t�1 |t�1 and covariance of the state estimate ⌃t�1 |t�1using the dynamics given by eq. (1),

x̂t |t�1 = f (x̂t�1 |t�1, ut ) (3)⌃t |t�1 = Ft⌃t�1 |t�1FT

t+Qt, (4)

where Ft = @ f /@x | x̂t�1|t�1.

Next, we incorporate information from noisy sensor obser-vations to update the state estimate. To do this, we utilize aobservation model given by zt = h(xt )+vt , where vt ⇠ N (0, R),and the following update equations:

Kt = ⌃t |t�1HT

t

⇣Ht⌃t |t�1HT

t+ R

⌘�1(5)

x̂t |t = x̂t |t�1 + Kt

�zt � h(x̂t |t�1)

�(6)

⌃t |t = (I � KtHt ) ⌃t |t�1 (7)

where zt are the actual sensor measurements and Ht =@h/@x | x̂t�1|t .

The observations in our EKF formulation use the kinematicmodel shown in fig. 1. We calibrate this model using groundtruth data from a VICON motion capture system. In ourapplication we incorporate three observations:

1) The expected measurement vector from the IMU’s ac-celerometer is primarily due to gravity and thus pointsup in the global coordinate frame. As ROI represents thecoordinate system rotation between the global frame O andthe IMU’s frame I, we expect the measured accelerationameas to align with the third row of ROI ,

h1(xt ) = {ROI(q)}row 3 (8)z1 = ameas (9)

2) The expected LIDAR measurement given the position ofthe IMU,

h2(xt ) =�` :

�pOLIDf (xt, `)

row 3 = 0

(10)

z2 = `meas, (11)

where pOLIDf is the location of the laser beam endpoint rep-resented in the global coordinate system, ` = k��������!LID0LIDf kis the modeled laser beam length, and `meas is the actualmeasured LIDAR distance.

Page 3: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

3) During stance, the toe point coincides with the origin(active 200 ms after stance begins until toe-o�)

h3(xt ) = pOT(xt, ✓k, ✓a) (12)z3 = [0 0 0]T (13)

where pOT describes the location of the toe in the inertialframe as a function of the EKF’s state estimate xt andthe knee ✓k and ankle ✓a angles, which are measured bythe prosthesis’ joint encoders. This observation is inspiredby previous work on pedestrian tracking across multiplesteps, in which a pseudomeasurement constrains the IMUvelocity to zero during stance [5].

The measurement noise for these observations is given by

R =�2a

I3⇥3 00 �2

l

�(14)

during swing and

R =266664�2a

I3⇥3 0 00 �2

` 00 0 �2

fI3⇥3

377775(15)

during stance. In these equations, �2a

is the accelerometervariance, �2

` is the LIDAR measurement variance, and �2f

isthe foot position variance.

To further improve the EKF’s state estimate, we enforce anumber of constraints using the methods provided by Gupta andHauser [7]. Specifically, we enforce three equality constraints:

1) First, we require that the quaternion has unit norm

1 = q21 + q2

2 + q23 + q2

4 . (16)

2) Second, we prevent the yaw component of the orientationq from drifting. To do this, we convert the q to ZYX Eulerangles and enforce �z = 0,

0 = atan2⇣2(q1q4 + q2q3), 1 � 2(q2

3 + q24)⌘. (17)

3) Finally, during stance we further constrain the toe’s x andy-coordinates to 0,

00

�= {pOT(xt, ✓k, ✓a)}rows 1 and 2. (18)

In addition, we use inequality constraints to ensure the toe andheel do not penetrate the ground,

0 {pOT(xt, ✓k, ✓a)}row 3, (19)0 {pOL(xt, ✓k, ✓a)}row 3. (20)

We enforce these constraints by solving the following quadraticprogram after each update step,

x̂projt |t = argmin

x

�x � x̂t |t

�T⌃�1t |t

�x � x̂t |t

�, (21)

such that

Aeqx = beq, (22)Aineqx = bineq, (23)

Ground Truth

EKF with Lidar

EKF without Lidar

Fig. 2: Trajectories of extended Kalman Filter (EKF) estimateof the position of the leg during swing (blue). Ground truthpositions given by motion capture (yellow). EKF estimatewithout LIDAR information shown in red. Thick lines showthe leg configuration at peak toe height during swing. Dottedlines indicate heel trajectories while dashed lines show the toetrajectories. Knee and ankle trajectories given by solid lines.

where Aeq, beq, Aineq, and bineq are derived from linearizingthe equality and inequality constraints. We found in practicethat solving this QP a single time resulted in a state estimatethat was su�ciently close to the constraints and that iterativelylinearizing the constraints and solving the QP was unnecessary.

To identify the appropriate parameters for the EKF, wecollected ground truth training and testing kinematic datausing a Vicon motion capture system. We optimized theparameters of the EKF by simulating the state estimator withdi�erent parameters and evaluating the resulting error betweenthe estimated trajectory and the ground truth trajectory. Theparameters we optimized were the rotation of the LIDAR withrespect to the hip, the translation between the LIDAR and theIMU, and �! , �a, �` , and �f .

Figure 2 shows an example of the resulting EKF estimatesof the hip, knee, ankle, heel, and toe positions during swing(blue stick figure and traces) compared to the ground truthobtained from the motion capture system (yellow) and an EKFestimate without the LIDAR sensor information integrated (red).Over the entire test data set, the root mean squared error of theestimated heel and toe positions during swing is 18.6 mm forthe EKF with LIDAR information. In contrast, the EKF withoutLIDAR information has an error of 46.7 mm. Thus, including

Page 4: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

the LIDAR sensor data reduces the error by 60%.

B. Gaussian Process Hip Trajectory Prediction

To predict the future hip trajectory, we learn Gaussian processmodels that describe the user’s hip height and angle versustime during the swing phase. We train these models with dataobtained from the specific user of the prosthesis during aninitial data collection period in which a standard minimum-jerkapproach generates the swing phase joint angle trajectories. Wespecifically train sparse Gaussian process models using the FITCapproximation [23] which ensures the computational complexityat test time is independent of the training data set size, therebyproviding consistent real-time performance. Throughout theswing phase, the learned hip angle and height distributions areconditioned on the swing trajectories completed so far to predictthe distribution of the future trajectories for the rest of the swing(example shown in fig. 3). Our algorithm then uses the meansof these conditional distributions in the motion planning phase(compare section II-C).

For example, to calculate the conditional mean of future hipangles, we first compute the joint distribution of completed (✓c

h)

and future (✓fh) hip angles,

P⇣✓ch, ✓f

h

⌘= N

�µfitc, ⌃fitc + K

�tjoint, tjoint

� �(24)

= N✓ µcµf

�,

⌃c,c ⌃c,f⌃f,c ⌃f,f

� ◆, (25)

where µfitc and ⌃fitc are obtained from equation 11 in [23] andK

�tjoint, tjoint

�is an additional noise term given by a rational

quadratic kernel [19] that correlates the predicted angles acrosstime, which results in smooth predicted trajectories. The meanof the conditional distribution P

⇣✓fh|✓ch

⌘is then given by

µcondf = µf + ⌃f,c⌃

�1c,c

�µc � ✓ch

�. (26)

As the inversion of ⌃c,c is the most computationally expensivecomponent of eq. (26), we use at most the last 10 hip angles andheights (sampled at 100 Hz) when calculating the conditionalmean (compare fig. 3).

C. Trajectory Planning Quadratic Program Formulation

To obtain reactive control of the prosthesis swing leg motioninside of the prosthesis’ existing Simulink Real-Time environ-ment, we plan future swing trajectories with a fast quadraticprogram (QP) operating at 100 Hz. The QP includes equalityconstraints, which ensure the trajectories progress smoothly fromthe current position to the desired end position, and inequalityconstraints, which avoid premature ground contact of the toeand heel of the prosthesis. Because in our formulation the QPcan only solve for one joint at a time, we first solve for the ankletrajectory assuming the knee trajectory found in the previoustime step and then use this updated ankle trajectory to solve forthe new knee trajectory.

Figure 4 provides more details of the actions of the trajectoryplanner algorithm. For example, at a time of about 150 ms into

−0.2

0.0

0.2

0.4

0.6

Hip

Angle(ra

d)

0.0 0.2 0.4 0.6Swing Time (s)

0.85

0.90

0.95

Hip

Heigh

t(m)

Joint Distribution

Conditional DistributionActual Trajectory/Conditional Points

Fig. 3: Example of hip angle and height trajectory predictions0.15 s into swing. The prediction algorithm uses the previous 10measured hip angles and heights (sampled at 100 Hz, black dots)along with the learned joint distributions of hip angles/heightsversus time (red) to obtain the conditional distributions of futurehip angles/heights (blue). The planning algorithm uses the meansof the conditional distributions to generate knee and ankletrajectories. The actual hip height and angle trajectories areshown in black.

the swing phase, the algorithm generates bounds for the kneethrough inverse kinematics (IK) by solving

✓toe bndk =

�✓k : {pOT(✓h, zh, ✓k, ✓a)}row 3 = 0

(27)

✓heel bndk

=�✓k : {pOL(✓h, zh, ✓k, ✓a)}row 3 = 0

(28)

at a set of sample times spanning the remaining swing trajectory.The QP then uses these bounds to plan the knee trajectory(red trace in fig. 4B). The ankle trajectory is found througha similar procedure. Figures 4C and E show the IK solutionsat characteristic points in the swing for the knee and anklerespectively, with solutions leading to toe contact shown inpurple and solutions leading to heel contact shown in yellow.For each contact point, there are typically two solutions, onelower bound, for which the joint angle cannot cross from above,and one upper bound, for which the joint angle cannot crossfrom below.

Often, the valid leg configurations span disjointed regions inthe configuration space (green and red regions in fig. 4B andD). Therefore, the planner next identifies a valid sequence ofregions for the trajectory to traverse in a four step procedure.First, the planner identifies critical points along the predictedtrajectory at which any bound activates or deactivates. Second,at each critical point, the planner sorts the bound angles from

Page 5: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

A

B

C

D

Knee

Boun

dsAn

kle

Boun

dsAn

kle

Angl

e(ra

d)Kn

ee A

ngle

(rad)

Swing Time (s)

Vide

oFr

ames

E

Knee

Ang

le(ra

d)

0.0 0.1 0.2 0.3 0.4 0.5

Completed Trajectory

Minjerk Trajectory

Planned Trajectory

ToeBounds

HeelBounds

On Path Regions

Off PathRegions

Selected Bounds

Fig. 4: Planning Algorithm Steps: Panels B and D show the generated knee and ankle trajectories respectively. The plannedtrajectory (red) lies within the computed bounds (dashed gray). In contrast, standard minimum jerk trajectories (blue) do notrespect the bounds, thereby increasing the tripping hazard. Panels C and E show examples of inverse kinematics (IK) solutionsfor toe (purple) and heel (yellow) contact for the knee and ankle joints respectively. We use the IK solutions to generate boundedregions that the planned trajectory can safely traverse. We consider ground contact constraints for only the first half of theremaining swing duration after which we only consider joint angle constraints. We use Dijkstra’s algorithm to select regions(green) that allow a path from the start point to the desired final point. Bounded regions that do not lie on the path are shown inred. Panel A shows the corresponding prosthesis motion.

Page 6: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

largest to smallest and iterates through them to define regionsbetween successive upper and lower bounds. Third, the plannerdefines a graph over the regions with edge weights equal to theaverage squared angle minus the volume of the child region.This cost favors a sequence of regions that are large and thussafe to travel trough and avoids regions that require excessivejoint flexion or extension. Dijkstra’s algorithm is then used tofind a valid sequence of regions that minimizes this cost [2].Finally, so that the generated trajectories do not get too closeto the identified bounds, a bu�er is added to the bounds. Thisbu�er takes the form

✓buf = ✓0buf sin

✓⇡

t � t0t f � t0

◆, (29)

where ✓0buf is either 5 � for lower bounds or -5 � upper bounds,t is the future swing time, and t0 and t f are the current andfinal swing times.

After identifying the bounded regions, the planner generatesthe trajectory for a specific joint by solving a quadratic program.The trajectory of each joint is represented by three, fifth-orderpolynomial splines,

✓1(t) = a01 + a11t + · · · + a51t5 = [1 t · · · t5]a1 (30)T0 t < T1 (31)...

✓3(t) = a03 + a13t + · · · + a53t5 = [1 t · · · t5]a3 (32)T2 t < TF, (33)

and solved for by the following QP,

a⇤ = argmina

12

aT (H✓ + wH›✓ )a, (34)

where a = [aT1 aT2 aT3 ]T , H✓ and H›✓ encode quadratic costs onangle and jerk respectively, and w is a weight parameter. Thesolution is subject to the inequality constraints

✓(t) ✓max(t), 8t (35)✓(t) � ✓min(t), 8t (36)€✓(t) €✓max, 8t (37)€✓(t) � €✓min, 8t, (38)

which ensure the trajectory lies within the identified bounds andrespects velocity limits, and to the equality constraints

✓(T0) = ✓0 (39)€✓(T0) = €✓0 (40)‹✓(T0) = ‹✓0 (41)✓(TF ) = ✓F (42)€✓(TF ) = 0 (43)‹✓(TF ) = 0 (44)✓1(T1) = ✓2(T1) (45)€✓1(T1) = €✓2(T1) (46)‹✓1(T1) = ‹✓2(T1) (47)

...

which ensure the trajectory starts at the current and terminatesat the desired positions, velocities, and accelerations and thatthe splines join together smoothly. If the QP fails to find atrajectory that can satisfy the constraints, the last found validtrajectory is reused for the next time step. In addition, at thefirst iteration, the ankle trajectory planner uses the output of theminimum jerk trajectory planner to solve the inverse kinematicsfor the bounds.

D. Experimental Procedure

We tested the ability of the proposed trip avoidance control toreduce the incidence and severity of trips while walking with thepowered transfemoral prosthesis shown in fig. 1 [25]. To evaluatethe performance of the system, an able-bodied user walked withthe prosthesis while attempting to elicit trips by lowering thehip in swing. During the stance phase, the prosthesis randomlydecided to either use the proposed swing control or to usestandard minimum jerk trajectories that do not consider thetripping hazard. The user was not aware of which controllerwould be used in the upcoming swing. The user completed atotal of ten one minute walking trials.

We examined several outcomes for evaluating control perfor-mance. First, we examined the distribution of knee angles atthe beginning of stance. Large knee angles at the beginningof stance indicate premature landing due to toe-strike insteadof heel strike. Ideally, the landing angle is close to the desiredfinal angle of 2 degrees. Second, we checked the integral of theground reaction force during swing. If this quantity is large, itindicates scu�ng of the toe on the ground. Finally, we examinedthe relationship between the hip and toe heights during swing.If our controller is working as intended, the toe height duringswing should have a decreased sensitivity to the hip height.

III. R������

Figure 5 shows the knee and ankle swing trajectoriesgenerated by the proposed control (blue) and by a standardjerk minimization control (red) during normal walking and tripelicitation. During undisturbed walking, the trajectories producedby both control strategies are similar. However, the proposedcontrol strategy has a tendency to keep the knee flexed forlonger and then extends it faster towards the end of swing. Inaddition, in a few steps, the proposed controller flexed the anklesignificantly more than did the standard minimum jerk control.These trends are exaggerated during trip elicitation. There aremore knee trajectories in which the knee stays flexed for longer,thereby creating more ground clearance. In addition, the ankleflexes earlier, which will help to create more foot clearancewhen the hip is suddenly lowered in early swing.

We used video and audio recordings of the trials, as wellas data from the prosthesis, to manually classify trips as thoseswing trajectories that end with toe strike or during which thefoot scu�ed on the ground. We find that over the ten minutesof walking, the minimum jerk control produced 109 trips whilethe proposed approach produced 35 trips, reducing the trip rateby 68%.

Page 7: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

0

30

60

90

Knee

Flexion

Angle(deg

)Normal

TrajectoriesTrip ElicitationTrajectories

0.0 0.2 0.4 0.6Swing Time (s)

−20

0

20

AnkleDorsifl

exion

Angle(deg

)

0.0 0.2 0.4 0.6

Proposed controlMinimum Jerk

Fig. 5: Knee and ankle trajectories produced during normalwalking and while eliciting trips. To avoid tripping during tripelicitation trials, trajectories generated by the proposed approachoften flex the knee to a greater degree and for longer beforequickly extending at the end of swing. At the ankle joint we seeoverall greater variability in the generated trajectories duringthe trip elicitation condition versus normal walking.

0.10

0.12

0.14Minimum Jerk ControlProposed Control

0 30 60 90Landing Knee Flexion Angle (deg)

0.000

0.005

0.010

Prob

abilityof

Knee

FlexionAn

gle

Propensity for Tripping

Fig. 6: Kernel density estimate of the probability of variouslanding knee flexion angles with the proposed swing control(blue) and standard min-jerk swing control (red). Large landingknee angles indicate premature toe contact during swing.

To further examine the performance of the two controlstrategies, we used kernel density estimates of the landingknee flexion angle, a measure of the propensity for tripping,and integrated ground reaction force (GRF) during swing, ameasure of the propensity for foot scu�ng. Figure 6 showsthe distributions of the landing angle of the prosthesis at theend of swing for the proposed swing control (blue) and forthe standard minimum jerk swing control (red) during the tripelicitation condition. We observe the minimum jerk control

0.15

0.20

0.25Minimum Jerk ControlProposed Control

0 5 10 15 20Integrated GRF (N-s)

0.000

0.025

0.050

Prob

ability

ofIntegrated

GRF

Propensity for Foot Scuffing

Fig. 7: Kernel density estimate of the probability of variousintegrated ground reaction force values for the proposed swingcontrol (blue) and standard min-jerk swing control (red). Largeintegrated GRF during the swing phase is indicative of the toescu�ng on the ground.

is much more likely to generate a swing trajectory that endsprematurely with a large knee flexion angle, which is indicativeof toe contact instead of heel contact at the end of swing. Thedistributions of the integrated GRFs suggests the minimumjerk control produced a larger percentage of swings with highground reaction forces than the proposed control, indicating anincreased frequency and severity of toe scu�ng during swing(fig. 7).

We can also ask the question, “For steps during which theprosthesis used trajectories generated by the proposed control,would the user have tripped had the prosthesis used a minimumjerk trajectory?” To answer this question, we can use thekinematics model shown in fig. 1 along with ground truthhip height and hip angle data captured via a motion capturesystem, to estimate the location of the toe had the knee andankle perfectly followed the desired trajectories produced byeach control scheme. This analysis predicts that the prosthesiswould have tripped or scu�ed the toe on the ground during 22%of the steps if we had used the minimum jerk trajectory. Incontrast, it predicts a trip or scu� rate of 5% had we perfectlyfollowed the trajectories generated by the proposed control.

Finally, fig. 8 shows the relationship between the average toeand hip heights during swing for both control schemes. Thetoe height of the prosthesis, when controlled by the proposedcontrol, is less sensitive to decreases in the hip height than it iswhen using the standard minimum jerk control.

IV. D���������

We presented initial work toward a real-time reactive controlof powered prostheses to help amputees avoid tripping inthe swing phase of gait. At any time during swing, theproposed control uses a laser range finder and an inertial

Page 8: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

820 855 890 925 960Average Hip Height (mm)

20

40

60

80

100

Averag

eToeHeigh

t(mm)

Minimum Jerk ControlProposed Control

Fig. 8: Average toe height vs average hip height for the proposedswing control (blue) and standard min-jerk swing control (red).The toe height during swing is less sensitive to the hip heightwhen using the proposed swing control than when using themin-jerk swing control.

measurement unit to estimate the current pose of the prostheticleg, predict the future hip angle and height based on trainedGaussian process models, and plan new knee and ankle jointtrajectories that ensure neither the toe nor heel contact theground prematurely. Our results indicate the proposed controlapproach can substantially reduce the incidence of trips andreduce the severity and frequency of toe scu�ng.

To the best of our knowledge, this work is the first demonstra-tion of lower limb prosthetic control that integrates perceptionfeedback in real-time and that proactively ameliorates the fallinghazard amputees face. Previous research in this area has largelyfocused on detecting stumbles after they have occurred. Forexample, Lawson et al. [11] and Shirota et al. [22] have proposedclassifiers that can detect trips during swing and predict whethera lower or raising strategy should be used in response. Similarly,Zhang et al. [26] have proposed a method that can detectstumbles and classify them as trips during swing or slipsduring stance. However, these previous studies have not proposedconcrete control actions to preempt stumbles or to properly reactin the event that a stumble is detected. Our results motivatefurther research into such proactive and reactive approaches,closing the perception-action loop for improving gait robustnesswith robotic prostheses.

Several avenues for future work exist. First, in our currentstudy, only one able-bodied user tested the proposed control.Further experiments with amputee subjects are needed to verifythe system provides benefits to this population. For instance,amputees accustomed to walking with passive prostheses showsignificantly altered hip kinematics [9], which could a�ect thecontrol behavior. However, the proposed control should be ableto properly adapt to these behavior di�erences, as the Gaussianprocess models are trained for specific users. Second, althoughtrips during swing are one of the most common failure modes

we encounter with our powered prostheses, these events are stillrare and many hours of normal walking are required to observea su�cient number of trips to compare controllers. As a result,we actively induced trips by sudden drops in hip height duringswing, which does not exactly reflect the situations in whichtrips occur. Specifically, trips can happen due to subtle changesin leg kinematics, and it remains to be seen in experiments ifour approach can avoid trips in these more subtle situations.

At the implementation level, there is also room for furtherexploration. To keep the computational costs low and to facilitateimplementation in Simulink Real-time, we used quadraticprograms that iterate between finding solutions for the ankle andknee joints. While this iterative approach is fast when comparedto trajectory optimization methods that deal with multiple jointssimultaneously, the iterations occasionally get stuck when theplanner for one joint trajectory cannot find a solution based onthe assumed fixed trajectory of the other joint. Moreover, if asolution cannot be found, the current approach simply reusesthe last identified trajectory, rather than moving the trajectoryto be more safe, even if it cannot fully satisfy the bounds. Itseems worthwhile to investigate whether non-convex trajectoryoptimization methods such as CHOMP [20], in which the boundsare represented as soft rather than hard constraints, can helpsolve for the knee and ankle trajectories simultaneously withoutsacrificing computational speed.

In addition, several technical simplifications can be consideredto bring this technology closer to commercialization. We usedan accurate and relatively expensive laser distance sensor,eyeing future research toward obstacle scanning and avoidancecapabilities. However, for simple ground plane avoidance,inexpensive infrared distance sensors such as those used byScandaroli et al. [21] are likely su�cient. It may also bepossible to simplify the trajectory planning phase by, for example,forgoing formal guarantees on satisfying bounds and insteadrelying on heuristics to increase knee and ankle flexion andadjust timing in response to decreased hip height during swing.

Our immediate goal, however, is to generalize the presentedapproach to incorporating perception in control beyond theavoidance of flat ground. We are currently investigating how toextend the approach to plan trajectories around obstacles thatare scanned by the laser range finder. Previous studies such asMohagheghi et al. [17] with able-bodied subjects have shownthat vision plays a crucial role in both planning and controlof the lower limb motion over obstacles. We also envisionusing the approach to target objects instead of avoiding them.For example, a prosthetic leg could scan, recognize, and targetsecure footholds and stair treads, or provide enhanced sportscapabilities by targeting and kicking a ball.

R���������[1] Brian DO Anderson and John B Moore. Optimal filtering.

Englewood Cli�s, 21:22–95, 1979.[2] Edsger W Dijkstra. A note on two problems in connexion

with graphs. Numerische mathematik, 1(1):269–271, 1959.[3] Lin Du, Fan Zhang, Ming Liu, and He Huang. Toward

design of an environment-aware adaptive locomotion-mode-

Page 9: Real-Time Reactive Trip Avoidance for Powered Transfemoral ...rss2019.informatik.uni-freiburg.de/papers/0119_FI.pdf · compare our method for trip avoidance to a standard non-reactive

recognition system. IEEE Transactions on BiomedicalEngineering, 59(10):2716–2725, 2012.

[4] Ran Duan, Shuangyue Yu, Guang Yue, Richard Foulds,Chen Feng, Yingli Tian, and Hao Su. Real-time robust3d plane extraction for wearable robot perception andcontrol. In 2018 Design of Medical Devices Conference,pages V001T06A003–V001T06A003. American Societyof Mechanical Engineers, 2018.

[5] E Foxlin. Pedestrian tracking with shoe-mounted inertialsensors. IEEE Computer Graphics and Applications, 25(6):38–46, 2005.

[6] Christiane Gauthier-Gagnon, Marie-Claude Grisé, andDiane Potvin. Enabling factors related to prosthetic useby people with transtibial and transfemoral amputation.Archives of physical medicine and rehabilitation, 80(6):706–713, 1999.

[7] Nachi Gupta and Raphael Hauser. Kalman filtering withequality and inequality state constraints. arXiv preprintarXiv:0709.2791, 2007.

[8] Yoshiaki Hayashi and Kazuo Kiguchi. A lower-limbpower-assist robot with perception-assist. In 2011 IEEEInternational Conference on Rehabilitation Robotics, pages1–6. IEEE, 2011.

[9] Sonja MHJ Jaegers, J Hans Arendzen, and Henry Jde Jongh. Prosthetic gait of unilateral transfemoralamputees: a kinematic study. Archives of physical medicineand rehabilitation, 76(8):736–743, 1995.

[10] Nili Eliana Krausz, Tommaso Lenzi, and Levi J Hargrove.Depth sensing for improved control of lower limb prosthe-ses. IEEE Transactions on Biomedical Engineering, 62(11):2576–2587, 2015.

[11] Brian E Lawson, H Atakan Varol, Frank Sup, and MichaelGoldfarb. Stumble detection and classification for an intelli-gent transfemoral prosthesis. In 2010 Annual InternationalConference of the IEEE Engineering in Medicine andBiology, pages 511–514. IEEE, 2010.

[12] Tommaso Lenzi, Levi Hargrove, and Jonathon Sensinger.Speed-adaptation mechanism: Robotic prostheses can ac-tively regulate joint torque. IEEE Robotics & AutomationMagazine, 21(4):94–107, 2014.

[13] Ming Liu, Ding Wang, and He Helen Huang. Developmentof an environment-aware locomotion mode recognition sys-tem for powered lower limb prostheses. IEEE Transactionson Neural Systems and Rehabilitation Engineering, 24(4):434–443, 2016.

[14] Sebastian Madgwick. An e�cient orientation filter forinertial and inertial/magnetic sensor arrays. Technicalreport, University of Bristol (UK), 2010.

[15] Yerzhan Massalin, Madina Abdrakhmanova, andHuseyin Atakan Varol. User-independent intentrecognition for lower-limb prostheses using depth sensing.IEEE Transactions on Biomedical Engineering, 2017.

[16] William C Miller, Mark Speechley, and Barry Deathe. Theprevalence and risk factors of falling and fear of fallingamong lower extremity amputees. Archives of physical

medicine and rehabilitation, 82(8):1031–1037, 2001.[17] Amir A Mohagheghi, Renato Moraes, and Aftab E Patla.

The e�ects of distant and on-line visual information onthe control of approach phase and step over an obstacleduring locomotion. Experimental Brain Research, 155(4):459–468, 2004.

[18] David Quintero, Dario J Villarreal, and Robert D Gregg.Preliminary experiments with a unified controller for apowered knee-ankle prosthetic leg across walking speeds.In Proceedings of the... IEEE/RSJ International Conferenceon Intelligent Robots and Systems. IEEE/RSJ InternationalConference on Intelligent Robots and Systems, volume2016, page 5427. NIH Public Access, 2016.

[19] Carl Edward Rasmussen. Gaussian processes in machinelearning. In Advanced lectures on machine learning, pages63–71. Springer, 2004.

[20] Nathan Ratli�, Matt Zucker, J Andrew Bagnell, andSiddhartha Srinivasa. Chomp: Gradient optimizationtechniques for e�cient motion planning. In Robotics andAutomation, 2009. ICRA’09. IEEE International Confer-ence on, pages 489–494. IEEE, 2009.

[21] Glauco Garcia Scandaroli, Geovany Araújo Borges,João Yoshiyuki Ishihara, Marco Henrique Terra, Adson Fer-reira da Rocha, and Francisco Assis de Oliveira Nasci-mento. Estimation of foot orientation with respect toground for an above knee robotic prosthesis. In Intelligentrobots and systems, 2009. IROS 2009. IEEE/RSJ interna-tional conference on, pages 1112–1117. IEEE, 2009.

[22] Camila Shirota, Ann M Simon, and Todd A Kuiken.Recovery strategy identification throughout swing phaseusing kinematic data from the tripped leg. In 2014 36thAnnual International Conference of the IEEE Engineeringin Medicine and Biology Society, pages 6199–6202. IEEE,2014.

[23] Edward Snelson and Zoubin Ghahramani. Local andglobal sparse gaussian process approximations. In ArtificialIntelligence and Statistics, pages 524–531, 2007.

[24] Frank Sup, Huseyin Atakan Varol, Jason Mitchell,Thomas J Withrow, and Michael Goldfarb. Prelimi-nary evaluations of a self-contained anthropomorphictransfemoral prosthesis. IEEE/ASME Transactions onmechatronics, 14(6):667–676, 2009.

[25] Nitish Thatte. Design and Evaluation of Robust ControlMethods for Robotic Transfemoral Prostheses. PhD thesis,Pittsburgh, PA, May 2019.

[26] Fan Zhang, Susan E D’Andrea, Michael J Nunnery,Steven M Kay, and He Huang. Towards design of a stumbledetection system for artificial legs. IEEE Transactions onNeural Systems and Rehabilitation Engineering, 19(5):567–577, 2011.

[27] Fan Zhang, Zheng Fang, Ming Liu, and He Huang.Preliminary design of a terrain recognition system. InEngineering in medicine and biology society, EMBC, 2011annual international conference of the IEEE, pages 5452–5455. IEEE, 2011.