2018-06-16 Underactuated Bipedal Robotic

Model Predictive Control of Underactuated Bipedal Robotic Walking

http://ames.gatech.edu/icra2015_iompc.pdf


Model Predictive Control of Underactuated Bipedal Robotic Walking

Matthew J. Powell, Eric A. Cousineau, and Aaron D. Ames

Abstract— This paper addresses the problem of controlling

underactuated bipedal walking robots in the presence of actuator

torque saturation. The proposed method synthesizes

elements of the Human-Inspired Control (HIC) approach for

generating provably-stable walking controllers, rapidly exponentially

stabilizing control Lyapunov functions (RES-CLFs)

and standard model predictive control (MPC). Specifically, the

proposed controller uses feedback linearization to construct a

linear control system describing the dynamics of the walking

outputs. The input to this linear system is designed to be the

solution of a MPC-based Quadratic Program which minimizes

the sum of the values of a RES-CLF–describing the walking

control objectives–over a finite-time horizon. Future values

of the torque constraints are mapped into the linear control

system using the Hybrid Zero Dynamics property of HIC

and subsequently incorporated in the Quadratic Program. The

proposed method is implemented in a rigid-body dynamics

simulation and initial experiments with the Durus robot.

I. INTRODUCTION

Model-based control of bipedal robotic walking can be

broadly classified into two groups, low-dimensional and

high-dimensional model-based controllers. In the former,

some approaches utilize models related to the dynamics of

the robot’s center of mass in the design of controllers which

dictate the aggregate behavior of the robot. The most common

low-dimensional models incorporated in robot walking

controllers are the Linear Inverted Pendulum [10], [12], [19],

[22], the Spring-Loaded Inverted Pendulum [8], and the full

nonlinear center of mass dynamics [12]. An advantage shared

by most low-dimensional walking controllers is that they

can be implemented in real-time control systems. However,

when formal hybrid stability of the walking controller is

required, as determined through Poincare analysis [15], the

full (high-dimensional) dynamics must be considered and

thus, controller generation cannot generally be solved in realtime.

These methods include direct trajectory optimization

[18], Hybrid Zero Dynamics [9], and the method discussed

in this paper, Human-Inspired Control [1], among others.

Due to the complexity of the high-dimensional model, these

optimization problems generally have to be solved apriori,

or “offline”, producing optimal control parameters that can

then be implemented “online” through local nonlinear control.

This paper presents an alternative, Model-Predictive

Control, approach to the online implementation of walking

gaits obtained apriori through the Human-Inspired Control

framework.

Matthew J. Powell, Eric A. Cousineau, and Aaron D. Ames are with the

Department of Mechanical Engineering, Texas A&M University, College

Station, TX 77843. {mjpowell,eacousineau,aames}@tamu.edu

This research is supported by NASA grants NNX11AN06H and

NNX12AQ68G, NSF grants CPS-1239085, CNS-0953823 and CNS-

1136104, and the Texas Emerging Technology Fund.

The goal of the Human-Inspired Control approach is to

produce exponentially stable periodic orbits–corresponding

to stable walking–in a hybrid system model of the robot. This

goal is realized by using constrained nonlinear optimization

to produce parameterized functions of the robot’s state,

termed virtual constraints or outputs, whose corresponding

zero dynamics surface is invariant through impact, i.e. foot

strike. After solving the optimization offline, the walking

gait is implemented online via nonlinear control, in the

form of feedback linearization [20] or rapidly exponentially

stabilizing control Lyapunov functions (RES-CLF) [2], to

locally stabilize the control objectives and in doing so,

stabilize the periodic orbit corresponding to walking.

The nonlinear optimization problem can include additional

constraints, such as actuator torque limits; however, overly

restrictive constraints can render the problem infeasible.

Recent work [7] addresses torque constraints through an

online controller that uses a Quadratic Program (QP) to

solve for torques that achieve rapid exponential stability of

a Lyapunov function describing the walking outputs while

simultaneously satisfying actuator torque limits. However, in

general, convergence constraints and torque limits may not

always be feasible, so a relaxation factor is added to the QP

to allow for violation of the CLF constraint. This produces

a locally optimal solution but does not guarantee behavior

of the controller over an extended period of time. As a step

toward guaranteeing forward horizon behavior of the RESCLF

under torque saturation, the controller proposed in this

paper uses Model Predictive Control: a control framework

that reasons about future convergence under input saturation.

The main contribution of this paper is an online controller

which combines elements of Human-Inspired Control for

bipedal robotic walking [1], the RES-CLF QP [3], [2], [7]

and standard Model Predictive Control (MPC) [5], [11], [14].

The present MPC setup is most similar to the approach

of [13] in which linear MPC methods are applied to the

linear input/output control system obtained through feedback

linearization of a nonlinear process. In the present method,

elements of [13] are explictly computed in the context of

Human-Inspired Control. In particular, the linear input/output

control system obtained through feedback linearization of

the human-inspired outputs is converted into a discrete-time

system and used to construct a linear MPC-based quadratic

program which minimizes the sum of the values of the RESCLF

over an extended period of time. Torque constraints

in the nonlinear robot dynamics are mapped into the linear

MPC-based QP through a procedure that uses Hybrid Zero

Dynamics to estimate the future states of the robot. The end

result extends the (local) RES-CLF QP to an MPC problem.

II. CONTROL OF ROBOTIC WALKING

This section presents an overview of the continuous-time

component of the Human-Inspired Control (HIC) approach

for underactuated bipedal robotic walking [1]. The goal

of HIC is to produce exponentially stable periodic orbits–

corresponding to stable walking–in a hybrid system model of

the robot. This goal is realized by producing walking control

objectives, or outputs, whose corresponding zero dynamics

surface is invariant through impact, i.e. foot strike. Nonlinear

control, in the form of feedback linearization [20] or rapidly

exponentially stabilizing control Lyapunov functions [2], is

used to locally stabilize the control objectives and in doing

so, stabilize the periodic orbit corresponding to walking. The

following paragraphs briefly cover the construction of the

continuous-time controller in the context of HIC.

A. Control System Model

Consider a model of an underactuated robot comprised of

n rigid links and m = n − 1 actuated revolute joints. Let

θ = (θb, θa) ∈ Q ⊂ R

n denote a vector of body coordinates

with θa ⊂ R

m a vector of “actuated joint angles” and θb ∈ R

a passive joint angle. Given this choice of coordinates, the

standard robot manipulator dynamics (see [17], [21]) can be

expressed as

D(θ)

¨θ + C(θ, ˙θ)

˙θ + G(θ) = Bu, (1)

with inertia matrix D(θ), Coriolis matrix C(θ, ˙θ), gravity

vector G(θ), actuator torque vector u ∈ R

m and torque

distribution matrix B. For more details on the specific model

considered in this paper, see [4]. These dynamics can be used

to express a general nonlinear control system for the robot:

x˙ = f(x) + g(x)u, (2)

in which x = (θ, ˙θ)

T ∈ T Q. In the Human-Inspired Control

approach, the goal is to realize exponentially stable periodic

orbits in a hybrid system representation of the robot; the

details of which are given in [1]. In the context of this paper,

it suffices to say that the hybrid system is comprised of

the continuous-time dynamics (2) and a discrete update law

describing the post-impact state, x

+ = (θ

+,

˙θ

+)

T

, following

an inelastic collision of the robot with the ground:

x

+ = ∆(x), if x ∈ S, (3)

where S is the guard and ∆ is the reset map of the hybrid system.

To this end, a parameterized feedback control, u(x, α) is

designed through careful construction of control objectives,

or outputs, as described in the following paragraph.

B. Human-Inspired Control Objectives

In the Human-Inspired Control framework, the goal of

effecting walking on the robot is realizing by driving continuous

functions of the robot’s joint angles to corresponding

desired values, whose form is motivated by observations of

human walking data [1]. The process involves constructing

outputs y(θ) ∈ R

m whose zeros correspond to a periodic

orbit in the hybrid system. Continuous-time controllers, are

designed to produce u that exponentially stabilize y(θ) → 0.

0 0.1 0.2 0.3 0.4 0.5 0.6 0.7

−0.3

−0.2

−0.1

0

0.1

0.2

0.3

0.4

0.5

0.6

0.7

Time (s)

Output

δmd

nsl θ

d

sk θ

d

nsk θ

d

tor

−0.6 −0.4 −0.2 0 0.2 0.4 0.6 0.8

−3

−2

−1

0

1

2

3

Angle (rad)

Velocity (rad/s)

θsa θsk θsh θnsh θnsk

Fig. 1. Human-Inspired Walking Outputs (Left) and Periodic Orbits (Right).

See [1], [4] for specific definitions of the robot joint angles and constructions

of the walking outputs used in this paper.

The final form (see [4] for specific constructions used for

the simulation and experiment examples in this paper) of

these outputs is

y(θ) = y

a

(θ) − y

d

(τ (θ), α), (4)

where y

a

(θ) is a vector of “actual” outputs and y

d

(τ (θ), α)

is a vector of “desired” outputs. The actual outputs can be

nonlinear functions, but they most often take a linear form:

y

a

(θ) = Hθ, (5)

where H ∈ R

m×n has full (row) rank. The desired behaviors

are encoded by the solution of an underdamped second order

system:

ycwf (t, α) = e

−α4t

(α1 cos(α2t) + α3 sin(α2t)) + α5. (6)

This function is made state-based through the substitution

t → τ (θ), with τ (θ) given by

τ (θ) = phip(θ) − phip(θ

+)

vd

, (7)

and where phip(θ) := cθ, c ∈ R

1×n, is the linearized

forward position of the hip, and vd is the walking speed

of the robot. This particular parameterization of time is

based on the observation that the forward position of the

hip during walking evolves nearly linearly with respect to

time. Substituting (7) into (6), the final form of the desired

outputs, as shown in (4), becomes:

y

d

(τ (θ), α) = [ycwf (τ (θ), αi

)]i∈O, (8)

in which O is an indexing set used to match desired

outputs with corresponding actual values. Associated with

the parameters α is a zero dynamics surface:

Zα = {(θ, ˙θ) ∈ T Q : y(θ) = 0, Lf y(θ, ˙θ) = 0}, (9)

on which the robot’s actual behavior is identical to the

prescribed desired behavior. In the Human-Inspired Control

method, an optimization problem is solved to obtain parameters

α

that satisfy hybrid invariance of Zα:

∆(S ∩ Zα) ⊂ Zα. (10)

Theorem 3 of [1] gives conditions on α which, when satisfied

in conjunction with (10), result in the existence of an

exponentially stable periodic orbit (a stable walking gait) in

a full-state hybrid system representation of the robot.

C. Local Nonlinear Control

This section describes nonlinear control methods which

can be employed to exponentially stabilize the humaninspired

walking outputs (4) within the robot control system

(2). In particular, feedback linearization [20] can be used to

achieve an arbitrary convergence rate when torque bounds

are not considered. However, in the control of robotic locomotion,

torque bounds cannot generally be neglected and

thus a more sophisticated approach, like the one described

in [2], [7], is required.

Input/Output (Feedback) Linearization. As the humaninspired

outputs, y(θ), have vector relative degree two in

the robot control system (2), the input/output linearization

control law for these outputs is

u = A

−1

(−Lf + µ), (11)

where A := LgLf y(θ) and Lf := L

2

f

y(θ, ˙θ) are Lie

derivatives along the vector fields f(x) and g(x) and the

dependence on (θ, ˙θ) has been suppressed for brevity. Here

the decoupling matrix A is assumed to be invertible and can

be made so through proper construction of control outputs

y(θ). Applying (11) to (2) results in y¨ = µ. In the absence of

torque constraints, a common choice of µ places the closedloop

poles of the output dynamics at −1/ε,

µ = −

2

ε

y˙ −

1

ε

2

y, (12)

where 0 < ε < 1 determines the output convergence rate.

When torque constraints cannot be neglected, as is often the

case in robot locomotion, a more sophisticated method of

selecting µ is required.

Control Lyapunov Functions. The rapidly exponentially

stabilizing control Lyapunov Function (RES-CLF) framework

presented in [2] provides a method of simultaneously

satisfying torque constraints and achieving exponential stability.

Assuming the preliminary feedback (11) has been

applied, and defining the “output” coordinates η := (y, y˙)

T

,

results in the following linear system:

η˙ =

0 1

0 0 �

| {z }

F

η +

0

1

| {z }

G

µ. (13)

The method of [2] can be employed to construct a RES-CLF

for the system (13) of the form, Vε(η) = η

T Pεη,

Vε(η) = η

T

IεP Iε

| {z }

η, Iε := diag �

1

ε

I, I�

, (14)

where I is the identity matrix and P = P

T > 0 solves the

continuous time algebraic Riccati equations (CARE)

F

T P + P F − P GGT P + Q = 0 (15)

for Q = QT > 0. The time-derivative of (14) is given by

ε(η) = LF Vε(η) + LGVε(η)µ, (16)

where the Lie derivatives of Vε(η) along the vector fields F

and G are

LF Vε(η) = η

T

(F

T Pε + PεF)η, (17)

LGVε(η) = 2η

T PεG. (18)

To achieve rapid exponential stability, and thus meet the

requirements of a RES-CLF, the following inequality on V˙

ε

must be satisfied

LF Vε(η) + LGVε(η)µ +

γ

ε

Vε(η) ≤ 0 (19)

with γ = λmin(Q)/λmax(P). In [2], it is shown that by

applying a RES-CLF to the continuous-time robot control

system (2), the corresponding periodic orbit (walking gait) is

exponentially stabilized. The following paragraph describes

an existing method for implementing a RES-CLF controller.

RES-CLF Quadratic Program. In practice, determining a µ

that satisfies the RES-CLF constraint (in an optimal manner)

can be achieved through the solution of a quadratic program

(QP) [2]. Indeed, the structure of a QP facilitates inclusion of

any affine constraint on µ, including actuator torque limits:

u = A

−1

(−Lf + µ) ≤ umax, (20)

where umax ∈ R

m is a vector of the maximum torques that

the robot’s motors are capable of producing.

However, the linear system of inequalities on µ described

by both the RES-CLF convergence constraints (19) and the

torque bounds (20) is not guaranteed to have a feasible

solution; thus, a “relaxation” term δ > 0 is added to the

RES-CLF constraint:

LF Vε + LGVεµ ≤ −

γ

ε

Vε + δ, (21)

to allow Vε to drift (locally) in the presence of active

torque constraints. Using this relaxed form of the RES-CLF

constraint, the torque-bounded, RES-CLF quadratic program

of interest in this paper (first stated in [7], see [3] for

additional related QP constructions), is given by:

, δ∗

) = argmin

(µ,δ)∈Rm+1

µ

T µ + pδ2

(RES-CLF QP)

s.t. LF Vε + LGVεµ ≤ −

γ

ε

Vε + δ,

A

−1

(−Lf + µ) ≤ umax,

−A

−1

(−Lf + µ) ≤ umax,

where p > 0 penalizes violation of the RES-CLF constraint.

When there exists a µ that satisfies both the RES-CLF and

the torque constraints, the solution of (RES-CLF QP) is

equivalent to the min-norm controller [6]. However, when

the torque constraints become active, δ

∗ grows and the RESCLF

constraint violated. By penalizing δ

in the objective

function, the QP finds the minimum RES-CLF violation

needed to satisfy the torque bounds.

The RES-CLF QP solves for the locally optimal balance

between convergence and torque bounds, however, it does

not have the machinery to reason about the current globally

optimal choice. As an intermediate step between the RESCLF

and re-solving the nonlinear optimization, we propose

the following MPC approach.

III. MPC FOR BIPEDAL ROBOTIC WALKING

This section presents the main contribution of the paper:

a model predictive control scheme which produces a current

value of µ that is consistent with a finite-time forward

horizon plan which minimizes estimated future values of

the RES-CLF describing the walking control objectives and

satisfies future values of the torque constraints. The mapping

from constraints on torque to constraints on µ over the

forward horizon is calculated using a process which leverages

hybrid zero dynamics. The end result takes the form of a

quadratic program with linear constraints.

A. Discrete-Time Representation for Horizon Planning

The continuous-time dynamical system on the outputs

given in (13) can be rewritten in discrete state-space form:

ηk+1 =

1 ∆T

0 1 �

| {z }

F∆T

ηk +

0

∆T

| {z }

G∆T

µk. (22)

with discrete time-step ∆T > 0. Given an initial condition,

η0, and a sequence of control inputs, µ¯ =

{µ0, µ1, µ2, . . . , µk−1}, the value of η after k time-steps,

denoted ηk, can be obtained by successively computing (22).

The corresponding value of the RES-CLF is calculated

using (14):

Vε(ηk) = η

T

k Pεηk. (23)

The goal of the model-predictive control method for bipedal

robotic walking is to determine a sequence of control inputs

µ¯ that minimizes the sum of the RES-CLF computed N steps

in the future while satisfying torque constraints over the same

interval. The next section describes the computation of future

values of the torque constraints in the context of humaninspired

control.

B. Estimating Torque Constraints via Hybrid Zero Dynamics

Let xk = (θk,

˙θk)

T

represent the state of the robot

k time-steps in the future, and Ak := LgLf y(θk) and

Lf := L

2

f

y(θk,

˙θk) be the corresponding values of the Lie

derivatives of (4). Using the feedback linearization control

law (11), the relationship between µ and u after k time-steps,

denoted µk and uk respectively, is given by

uk = A

−1

k

(−Lf,k + µk). (24)

The goal of this section is to estimate future values of Ak and

Lf,k so that future torque bounds can be accurately predicted.

From [1], the zero dynamics coordinates corresponding to

the zero dynamics surface Zα given in (9) are

z1 = cθ, (25)

z2 = γ0(θ)

˙θ, (26)

with γ0(θ) the first row of the inertia matrix D(θ). Assuming

that we have used the Human-Inspired Optimization to obtain

parameters α

corresponding to a stable periodic orbit in the

0 0.2 0.4 0.6 0.8

−30

−20

−10

0

10

20

30

Time (s)

Torque (Nm)

usk ush unsh unsk

0 0.2 0.4 0.6 0.8

−30

−20

−10

0

10

20

30

Time (s)

Torque (Nm)

usk ush unsh unsk

Fig. 2. Feedforward torques corresponding to the nominal gait (left) and

RES-CLF QP torques with umax = 20. See [1], [4] for specific constructions

of the walking outputs used in this paper.

hybrid system model of our robot, the dynamics of (25) and

(26) along this orbit are given by:

z˙1 = cΨ(z1)z2, (27)

z˙2 =

∂V (θ)

∂θsf

θ=Φ(z1)

, (28)

where V (θ) is the potential energy of the robot and

Φ(z1) = �

c

H

�−1 �

z1

yd(z1)

, (29)

Ψ(z1) = �

γ0(Φ(z1))

H −

∂yd(z1)

∂z1

c

�−1 �

1

0

. (30)

It follows that on the zero dynamics surface, the angles

and velocities can be calculated as functions of z1 and z2,

θ = Φ(z1) and ˙θ = Ψ(z1)z2. Thus, to calculate the Lie

derivatives Ak and Lf,k, the zero dynamics (27) and (28) are

integrated k time steps in the future to produce z1,k and z2,k,

which can be used to calculate angles and velocities through

Φ(z1) and Ψ(z1), which can then be used to calculate Ak :=

LgLf y(Φ(z1,k)) and Lf,k := L

2

f

y(Φ(z1,k), Ψ(z1,k)z2,k).

C. MPC-QP for Bipedal Robotic Walking

We can now state the main contribution of the paper: a

MPC-based quadratic program which attempts to minimize

the values of the RES-CLF for robotic walking over an N

time-step forward horizon and to satisfy nonlinear torque

bounds over the same horizon (R = RT > 0):

µ¯

(x) = argmin

µ¯

η

T

N PεηN +

N

X−1

k=0

η

T

k Pεηk + µ

T

k Rµk (31)

s.t. ηk+1 = F∆T ηk + G∆T µk,

A

−1

k

µk ≤ u

max + A

−1

k L

2

f,k,

−A

−1

k

µk ≤ u

max − A

−1

k L

2

f,k,

η0 = η(x),

∀k ∈{0, 1, . . . , N − 1}.

The MPC-QP is implemented in real-time. At each x, the

zero dynamics coordinates are calculated using (25) and (26),

and integrated forward in time to produce Ak and Lf,k. The

optimization problem is then solved, and the first element in

the solution, µ

0

is used in the feedback linearization control

law (11), i.e. u = A−1

(−Lf + µ

0

).

0 0.2 0.4 0.6 0.8 −0.03

−0.02

−0.01

0

0.01

0.02

0.03

0.04

0.05

0.06

Time (s)

Output

δmnsl θsk θnsk θtor

0 0.2 0.4 0.6 0.8

−30

−20

−10

0

10

20

30

Time (s)

Torque (Nm)

usk ush unsh unsk

Fig. 3. Control outputs y (left) and torques u (right) from simulation using

the RES-CLF QP with umax = 20Nm.

0 0.2 0.4 0.6 0.8 −0.03

−0.02

−0.01

0

0.01

0.02

0.03

0.04

0.05

0.06

Time (s)

Output

δmnsl θsk θnsk θtor

0 0.2 0.4 0.6 0.8

−30

−20

−10

0

10

20

30

Time (s)

Torque (Nm)

usk ush unsh unsk

Fig. 4. Control outputs y (left) and torques u (right) from simulation using

the RES-CLF QP with umax = 9Nm.

IV. SIMULATION RESULTS

This section presents a simulation comparison of the

performance of the RES-CLF QP [2], [7] and the proposed

MPC-based control method for achieving bipedal robotic

walking. The dynamic model used in this simulation is

that of Durus, a robot designed and constructed by SRI

International, shown in Figure 7; specifics of the model,

including the coordinates, mass and length properties, can

be found in [4].

As part of a different project, the Human-Inspired Optimization

[1], [4] was solved to obtain parameters, α

, and a

fixed point, x

, corresponding to a stable walking gait on a

rigid-body dynamics model of the Durus robot. The desired

outputs (8), computed with α

, are shown in Figure 1, along

with the periodic orbit corresponding to x

. The nominal

torques (11) along this orbit are shown in Figure 2. Here,

these parameters are used to investigate the performance

properties of the RES-CLF QP and the proposed MPC under

non-trivial torque bounds.

A. RES-CLF QP

The first simulation case investigated is the feedback

linearization controller (11) with µ obtained from

(RES-CLF QP) under torque bounds of u

max = 20Nm,

ε = 1/50 and p = 1. Results from application of this

controller to the robot control system (2) over the course of

one continuous-time stride of walking are shown in Figure 3.

The plot of the outputs y shows divergence during the initial

0.1s of simulation, and the plot of the torques u shows that

one of the torques saturates during the same interval. After

the initial saturation, the outputs converge as expected.

0 0.2 0.4 0.6 0.8 −0.03

−0.02

−0.01

0

0.01

0.02

0.03

0.04

0.05

0.06

Time (s)

Output

δmnsl θsk θnsk θtor

0 0.2 0.4 0.6 0.8

−30

−20

−10

0

10

20

30

Time (s)

Torque (Nm)

usk ush unsh unsk

Fig. 5. Control outputs y (left) and torques u (right) from simulation using

the proposed MPC-based QP with umax = 20Nm.

0 0.2 0.4 0.6 0.8 −0.03

−0.02

−0.01

0

0.01

0.02

0.03

0.04

0.05

0.06

Time (s)

Output

δmnsl θsk θnsk θtor

0 0.2 0.4 0.6 0.8

−30

−20

−10

0

10

20

30

Time (s)

Torque (Nm)

usk ush unsh unsk

Fig. 6. Control outputs y (left) and torques u (right) from simulation using

the proposed MPC-based QP with umax = 9Nm.

In the second simulation of the (RES-CLF QP), more

rigorous torque bounds of u

max = 9Nm are enforced, while

the other configuration variables remain at ε = 1/50 and

p = 1. Results from simulation of this controller are given

in Figure 4. The plot of the outputs shows significantly

more divergence in this case, which is to be expected

given the more stringent torque bounds. The plot of the

corresponding torques, however, reveals longer periods of

saturation and a loss of continuity in the torque signal. This

(loss of Lipschitz continuity of the commanded torques) is a

recurring challenge with RES-CLF QP implementation [16].

B. MPC-QP for Bipedal Robotic Walking

The next two simulation case studies investigate the behavior

of the feedback linearization controller (11) with

µ obtained from the proposed MPC-based QP for bipedal

robotic walking (31) described in Section III. For both

simulations that follow, N = 5, ∆T = 0.01s, ε = 1/200

and R = 0.0001I, with I an identity matrix.

In the first of the two MPC-based QP simulations, the

torque bound is set to u

max = 20Nm. Figure 5 shows outputs

and torques from this simulation, in which it can be seen that

(31) performs in a similar manner to (RES-CLF QP) under

the same torque bounds.

In the second of the two MPC-based QP simulations, the

torque bound is set to u

max = 9Nm. Figure 6 shows outputs

and torques from this simulation, in which it can be seen

that the outputs y diverge in a similar manner as the outputs

of the (RES-CLF QP) under the same torque bounds, but

the torques produced by the IO-MPC do not lose Lipschitz

continuity.

V. EXPERIMENTAL RESULTS AND FUTURE WORK

The proposed MPC-based controller for bipedal robotic

walking was implemented in C++ on the Durus robot using

an internal dynamics model integration method to convert

the feedback linearization torques into position and velocity

commands [4]. Data from an experiment in which the robot

successfully completed three laps around the room (63 steps)

is shown in Figure 7. The average phase portraits from

experiment agree quite well with the corresponding phase

portraits from simulation, presented earlier in Figure 1. In

the experiment phase portrait, bi-periodicity is apparent: this

is due to the fact that the boom which supports Durus does

not entirely enforce planar motion. A video of the experiment

is available online http://youtu.be/OG-WIfWMZek.

Formal stability of the hybrid periodic orbit as a result

of the proposed MPC control approach is a prime focus

of current research. Existing methods of proving stability

of the orbit rely on exponential stability of the continuoustime

controller, and to the authors’ knowledge, a proof of

stability under nontrivial torque saturation is still an open

problem. To address the hybrid stability problem, it will be

important to note existing methods of proving stability of

MPC controllers, such as those described in [14], impose

conditions on a terminal cost η

T

N PεηN . Zero dynamics play

a large part in the current work. Increasing the dimensionality

of the zero dynamics (such as going to 3D) poses significant

challenges that need to be addressed. A note on the method:

the proposed MPC problem is (currently) not intended to

replace the nonlinear optimization that produces the nominal

gait. Associated with the nominal gait is a feedforward

torque profile; deviations from these nominal torques will

necessarily change the gait. The standard approach would

be to re-solve the constrained nonlinear optimization for a

different gait with lower torque bounds; however, this comes

with its own challenges and it has to be done offline. Instead,

the current MPC formulation intends to be a step towards

handling (reasonable) torque bounds at the online control

implementation level, and thus, relieve some of the burden

of the offline optimization.

REFERENCES

[1] A. D. Ames. Human-inspired control of bipedal walking robots.

Automatic Control, IEEE Transactions on, 2014.

[2] A. D. Ames, K. Galloway, and J. W. Grizzle. Control lyapunov

functions and hybrid zero dynamics. In Decision and Control (CDC),

2012 IEEE 51st Annual Conference on, 2012.

[3] A. D. Ames and M. Powell. Towards the unification of locomotion

and manipulation through control lyapunov functions and quadratic

programs. In Control of Cyber-Physical Systems, Lecture Notes in

Control and Information Sciences. 2013.

[4] E. Cousineau and A. D. Ames. Realizing underactuated bipedal

walking with torque controllers via the ideal model resolved motion

method. IEEE International Conference on Robotics and Automation

(ICRA), 2015.

[5] J. Deng, V. Becerra, and R. Stobart. Input constraints handling in an

mpc/feedback linearization scheme. Int. J. Appl. Math. Comput. Sci.,

2009.

[6] R. A. Freeman and P. V. Kokotovic.´ Robust Nonlinear Control Design.

Birkhauser, 1996. ¨

[7] K. S. Galloway, K. Sreenath, A. D. Ames, and J. W. Grizzle.

Torque saturation in bipedal robotic walking through control lyapunov

function based quadratic programs. CoRR, abs/1302.7314, 2013.

−0.4 −0.2 0 0.2 0.4 0.6

−3

−2

−1

0

1

2

3

Angle (rad)

Velocity (rad/s)

θsa θsk θsh θnsh θnsk

0 0.5 1 1.5 2 2.5

−0.6

−0.4

−0.2

0

0.2

0.4

0.6

0.8

Time (s)

Angle (rad)

θ

a

sk θ

a

sh θ

a

nsh θ

a

nsk

θ

d

sk θ

d

sh θ

d

nsh θ

d

nsk

Fig. 7. Results from experiment of the proposed MPC-based QP for robotic

walking with Durus (right), showing phase portraits (top left) for 63 steps of

walking together with a darker averaged phase portrait and position tracking

errors (bottom left) over a select 4 steps in the same experiment.

[8] G. Garofalo, C. Ott, and A. Albu-Schaffer. Walking control of fully

actuated robots based on the bipedal slip model. In Robotics and

Automation (ICRA), 2012 IEEE International Conference on, 2012.

[9] J. W. Grizzle and E. R. Westervelt. Hybrid zero dynamics of planar

bipedal walking. In Analysis and Design of Nonlinear Control Systems.

2008.

[10] S. Kajita, F. Kanehiro, K. Kaneko, K. Fujiwara, K. Harada, K. Yokoi,

and H. Hirukawa. Biped walking pattern generation by using preview

control of zero-moment point. In Robotics and Automation, 2003.

Proceedings. ICRA ’03. IEEE International Conference on, 2003.

[11] X.-B. Kong, Y. jie Chen, and X. jie Liu. Nonlinear model predictive

control with input-output linearization. In Control and Decision

Conference (CCDC), 2012 24th Chinese, 2012.

[12] S. Kuindersma, F. Permenter, and R. Tedrake. An efficiently solvable

quadratic program for stabilizing dynamic locomotion. CoRR, 2013.

[13] M. J. Kurtz and M. A. Henson. Input-output linearizing control of

constrained nonlinear processes. Journal of Process Control, 1997.

[14] D. Q. Mayne, J. B. Rawlings, C. V. Rao, and P. O. M. Scokaert.

Survey constrained model predictive control: Stability and optimality.

Automatica, 2000.

[15] B. Morris and J. Grizzle. A restricted poincar’e; map for determining

exponentially stable periodic orbits in systems with impulse effects:

Application to bipedal robots. In Decision and Control, CDC-ECC.

44th IEEE Conference on, 2005.

[16] B. Morris, M. Powell, and A. Ames. Sufficient conditions for the

lipschitz continuity of qp-based multi-objective control of humanoid

robots. In IEEE Conference on Decision and Control (CDC), 2013.

[17] R. M. Murray, Z. Li, and S. S. Sastry. A Mathematical Introduction

to Robotic Manipulation. CRC Press, Boca Raton, 1994.

[18] M. Posa and R. Tedrake. Direct trajectory optimization of rigid body

dynamical systems through contact. In Algorithmic Foundations of

Robotics X, Springer Tracts in Advanced Robotics. 2013.

[19] J. Pratt, J. Carff, and S. Drakunov. Capture point: A step toward

humanoid push recovery. In 6th IEEE-RAS International Conference

on Humanoid Robots, Genoa, Italy, 2006.

[20] S. S. Sastry. Nonlinear Systems: Analysis, Stability and Control.

Springer, New York, 1999.

[21] M. W. Spong and M. Vidyasagar. Robotic Dynamics and Control.

John Wiley and Sons, New York, NY, 1989.

[22] B. Stephens and C. Atkeson. Push recovery by stepping for humanoid

robots with force controlled joints. In International Conference on

Humanoid Robots, Nashville, Tennessee, 2010.

©著作权归作者所有,转载或内容合作请联系作者
  • 序言:七十年代末,一起剥皮案震惊了整个滨河市,随后出现的几起案子,更是在滨河造成了极大的恐慌,老刑警刘岩,带你破解...
    沈念sama阅读 194,457评论 5 459
  • 序言:滨河连续发生了三起死亡事件,死亡现场离奇诡异,居然都是意外死亡,警方通过查阅死者的电脑和手机,发现死者居然都...
    沈念sama阅读 81,837评论 2 371
  • 文/潘晓璐 我一进店门,熙熙楼的掌柜王于贵愁眉苦脸地迎上来,“玉大人,你说我怎么就摊上这事。” “怎么了?”我有些...
    开封第一讲书人阅读 141,696评论 0 319
  • 文/不坏的土叔 我叫张陵,是天一观的道长。 经常有香客问我,道长,这世上最难降的妖魔是什么? 我笑而不...
    开封第一讲书人阅读 52,183评论 1 263
  • 正文 为了忘掉前任,我火速办了婚礼,结果婚礼上,老公的妹妹穿的比我还像新娘。我一直安慰自己,他们只是感情好,可当我...
    茶点故事阅读 61,057评论 4 355
  • 文/花漫 我一把揭开白布。 她就那样静静地躺着,像睡着了一般。 火红的嫁衣衬着肌肤如雪。 梳的纹丝不乱的头发上,一...
    开封第一讲书人阅读 46,105评论 1 272
  • 那天,我揣着相机与录音,去河边找鬼。 笑死,一个胖子当着我的面吹牛,可吹牛的内容都是我干的。 我是一名探鬼主播,决...
    沈念sama阅读 36,520评论 3 381
  • 文/苍兰香墨 我猛地睁开眼,长吁一口气:“原来是场噩梦啊……” “哼!你这毒妇竟也来了?” 一声冷哼从身侧响起,我...
    开封第一讲书人阅读 35,211评论 0 253
  • 序言:老挝万荣一对情侣失踪,失踪者是张志新(化名)和其女友刘颖,没想到半个月后,有当地人在树林里发现了一具尸体,经...
    沈念sama阅读 39,482评论 1 290
  • 正文 独居荒郊野岭守林人离奇死亡,尸身上长有42处带血的脓包…… 初始之章·张勋 以下内容为张勋视角 年9月15日...
    茶点故事阅读 34,574评论 2 309
  • 正文 我和宋清朗相恋三年,在试婚纱的时候发现自己被绿了。 大学时的朋友给我发了我未婚夫和他白月光在一起吃饭的照片。...
    茶点故事阅读 36,353评论 1 326
  • 序言:一个原本活蹦乱跳的男人离奇死亡,死状恐怖,灵堂内的尸体忽然破棺而出,到底是诈尸还是另有隐情,我是刑警宁泽,带...
    沈念sama阅读 32,213评论 3 312
  • 正文 年R本政府宣布,位于F岛的核电站,受9级特大地震影响,放射性物质发生泄漏。R本人自食恶果不足惜,却给世界环境...
    茶点故事阅读 37,576评论 3 298
  • 文/蒙蒙 一、第九天 我趴在偏房一处隐蔽的房顶上张望。 院中可真热闹,春花似锦、人声如沸。这庄子的主人今日做“春日...
    开封第一讲书人阅读 28,897评论 0 17
  • 文/苍兰香墨 我抬头看了看天上的太阳。三九已至,却和暖如春,着一层夹袄步出监牢的瞬间,已是汗流浃背。 一阵脚步声响...
    开封第一讲书人阅读 30,174评论 1 250
  • 我被黑心中介骗来泰国打工, 没想到刚下飞机就差点儿被人妖公主榨干…… 1. 我叫王不留,地道东北人。 一个月前我还...
    沈念sama阅读 41,489评论 2 341
  • 正文 我出身青楼,却偏偏与公主长得像,于是被迫代替她去往敌国和亲。 传闻我的和亲对象是个残疾皇子,可洞房花烛夜当晚...
    茶点故事阅读 40,683评论 2 335

推荐阅读更多精彩内容