Conference PaperPDF Available

Dynamic Locomotion in the MIT Cheetah 3 Through Convex Model-Predictive Control

Authors:
Dynamic Locomotion in the MIT Cheetah 3 Through Convex Model-Predictive Control
Jared Di Carlo1, Patrick M. Wensing2, Benjamin Katz3, Gerardo Bledt1,3, and Sangbae Kim3
Abstract This paper presents an implementation of model
predictive control (MPC) to determine ground reaction forces
for a torque-controlled quadruped robot. The robot dynamics
are simplified to formulate the problem as convex optimization
while still capturing the full 3D nature of the system. With
the simplified model, ground reaction force planning problems
are formulated for prediction horizons of up to 0.5 seconds,
and are solved to optimality in under 1 ms at a rate of 20-30
Hz. Despite using a simplified model, the robot is capable of
robust locomotion at a variety of speeds. Experimental results
demonstrate control of gaits including stand, trot, flying-trot,
pronk, bound, pace, a 3-legged gait, and a full 3D gallop. The
robot achieved forward speeds of up to 3 m/s, lateral speeds up
to 1 m/s, and angular speeds up to 180 deg/sec. Our approach
is general enough to perform all these behaviors with the same
set of gains and weights.
I. INTRODUCTION
Control of highly dynamic legged robots is a challenging
problem due to the underactuation of the body during many
gaits and due to constraints placed on ground reaction forces.
As an example, during dynamic gaits4such as bounding or
galloping, the body of the robot is always underactuated.
Additionally, ground reaction forces must always remain in
a friction cone to avoid slipping. Current solutions for highly
dynamic locomotion include heuristic controllers for hopping
and bounding [1], which are effective, but difficult to tune;
two-dimensional planar simplifications [2], which are only
applicable for gaits without lateral or roll dynamics; and
evolutionary optimization for galloping [3], which cannot
currently be solved fast enough for online use. Recent
results on hardware include execution of bounding limit
cycles discovered offline with HyQ [4] and learned pronking,
trotting, and bounding gaits on StarlETH [5].
Predictive control can stabilize these dynamic gaits by
anticipating periods of flight or underactuation, but is dif-
ficult to solve due to the nonlinear dynamics of legged
robots and the large number of states and control inputs.
Nonlinear optimization has been shown to be effective for
predictive control of hopping robots [6], humanoids [7], [8],
and quadrupeds [9], with [9] demonstrating the utility of
heuristics to regularize the optimization. Another common
approach is to use both a high-level planner, such as in [10],
[11] and a lower level controller to track the plan. More
Authors are with the 1Department of Electrical Engineering and
Computer Science at the Massachusetts Institute of Technology,
Cambridge, MA, 02139, USA; the 2Department of Aerospace and
Mechanical Engineering at the University of Notre Dame, Notre
Dame, IN, 46556; and the 3Department of Mechanical Engineer-
ing at the Massachusetts Institute of Technology, Cambridge, MA,
02139, USA. email: dicarloj@mit.edu,pwensing@nd.edu,
benkatz@mit.edu,gbledt@mit.edu,sangbae@mit.edu
4In this paper, the term dynamic gaits is used to refer to gaits with
significant periods of flight or underactuation.
Fig. 1. The MIT Cheetah 3 Robot galloping at 2.5 m/s
recently, the experimental results in [12] show that whole-
body nonlinear MPC can be used to stabilize trotting and
jumping.
The stabilization of the quadruped robot HyQ using con-
vex optimization discussed in [13] demonstrates the utility
of convex optimization, but the approach cannot be imme-
diately extended to dynamic gaits due to the quasi-static
simplifications made to the robot model. Similarly, in bipedal
locomotion, convex optimization has been used to find the
best forces to satisfy instantaneous dynamics requirements
[14] and to plan footsteps with the linear inverted pendulum
model [15] but the latter approach does not include orienta-
tion in the predictive model.
While galloping is well studied in the field of biology
[16], [17], surprisingly few hardware implementations of
galloping exist. The first robot to demonstrate galloping
was the underactuated quadruped robot Scout II [18], which
reached 1.3 m/s, but had limited control of yaw. The MIT
Cheetah 1 robot [19] achieved high-speed galloping, but
was constrained to a plane. To the best of our knowledge,
the only previous implementation of a fully 3D gallop with
yaw control is on the hydraulically actuated WildCat robot
[20], developed by Boston Dynamics. Unfortunately, no
specific details about WildCat or its control system have been
published.
The main contribution of this paper is a predictive con-
troller which stabilizes a large number of gaits, including
those with complex orientation dynamics. On hardware,
we achieved a maximum yaw rate of 180 deg/sec and a
maximum linear velocity of 3.0 m/s during a fully 3D gallop,
which we believe to be the fastest gallop of an electrically
actuated robot, and the fastest angular velocity of any legged
robot similar in scale to Cheetah 3. Our controller can be
formulated as a single convex optimization problem which
considers a 3D, 12 DoF model of the robot. The solution of
This work was supported by the National Science Foundation [NSF-IIS-
1350879] and the Air Force Office of Scientific Research [FA2386-17-1-
4661]
Operator
Input
Reference
Trajectory
MPC
(rigid body model) R>
i
State
Estimator
Swing Trajectory
(multi-body model)
Eq. (2)
Leg Position,
Torque,
Force Control
Eqs. (1), (4)
˙x, ˙y,
˙
ψ, cfiBfi
Kp, Kd,τff,Bpdes ,Bvdes
Fig. 2. Control system block diagram. The reference trajectory contains desired velocities and contact sequence from the operator. Blocks shaded blue
run at 30 Hz, blocks shaded red run at 1 kHz, and blocks shaded green run at 4.5 kHz.
x
z
z
y
x
y
MIT Cheetah 3
FL
FR
RL
RR
Body
World
Fig. 3. World and Body Coordinate Systems
the optimization problem can be directly used to compute
motor torques that stabilize the robot without the use of an
additional feedback controller.
The convex optimization approach has the benefit of avoid-
ing nonlinear optimization techniques, which, unlike convex
optimization solvers, are not guaranteed to find the global
optimum and may suffer from numerical issues. Recent
progress on convex optimization [21] and applications to
model predictive control [22] has led to the development of
many open source solvers such as ECOS [23] and qpOASES
[24] that enable model predictive control problems to be
solved rapidly and reliably.
The proposed controller was tested on the MIT Cheetah
3 quadruped robot on a treadmill and untethered on the
ground, where it was able to stand, trot, flying-trot, pace,
bound, pronk, and gallop. Aggressive turning maneuvers and
omnidirectional locomotion were tested as well. The robot
is powered by onboard batteries and all control calculations
are done on an onboard processor. During tests, the robot
encountered a number of obstacles and disturbances, in-
cluding a staircase with full size steps covered in debris,
which it was able to blindly climb with while doing a
flying trot. To handle the large terrain disturbances, the robot
used a contact detection algorithm described in [25]. For
all tests, including stair climbing, the robot uses no sensors
other than an inertial measurement unit (IMU), joint position
encoders, and current sensors in the motor controllers, with
the latter used only for a current control feedback loop.
The supplemental video includes highlights from testing.
Footage of complete tests is available online at: https:
//www.youtube.com/watch?v=q6zxCvCxhic.
This paper is organized as follows. Section II describes
the control framework used on the Cheetah 3 robot. The
dynamics model is presented in Section III, followed by the
model predictive control problem formulation in Section IV.
Section V contains implementation details and results.
II. CON TROL ARCHITECTURE
A. MIT Cheetah 3 Robot
The MIT Cheetah 3, shown in figure 1, is a 45 kg
quadruped robot built by the MIT Biomimetic Robotics Lab
[26]. The robot utilizes the proprioceptive actuator technol-
ogy developed for the Cheetah 2 robot [27], which had low
inertia, easily backdrivable hip and knee actuators to mitigate
impacts. Cheetah 3 uses the same actuator technology in its
hips, knees, and additionally the ab/ad joints, which allows
the robot to execute dynamic turns.
Each of the robot’s four legs has three torque controlled
joints: ab/ad, hip, and knee. Each joint can produce a
maximum torque of 250 Nm and can operate at a maximum
velocity of 21 rad/sec. Motor torque control is accomplished
by adjusting the setpoint of the motor current control loop;
there are no torque or force sensors.
B. Conventions
The body and world coordinate systems are defined in
Figure 3. All quantities in the body coordinate system have a
left subscript B. Quantities with no subscript are in the world
coordinate system. Vectors are bold, upright, and lowercase
(a,ω), matrices are bold, upright, and uppercase (A,),
and scalars are lowercase and italicized (a, ω). 1nis used
to denote an n×nidentity matrix.
C. State Machine
The controller proposed in this paper determines desired
3D ground reaction forces for behaviors with fixed-timing
foot placement and liftoff. When a foot is scheduled to be
in the air, the robot runs a swing leg controller, which is
robust to early touchdowns. Otherwise, a ground force con-
troller runs. These controllers are described in the following
subsections and in Figure 2.
D. Swing Leg Control
The swing controller computes and follows a trajectory
for the foot in the world coordinate system. The controller
for tracking the trajectory uses the sum of a feedback and
feedforward term to compute joint torques.
The control law used to compute joint torques for leg iis
τi=J>
i[Kp(Bpi,ref Bpi) + Kd(Bvi,ref Bvi)] + τi,ff
(1)
where JiR3×3is the foot Jacobian, Kp,KdR3×3are
diagonal positive definite proportional and derivative gain
matrices, Bpi,BviR3are the position and velocity of
the i-th foot, Bpi,ref,Bvi,ref R3are the corresponding
references for the position and velocity of the swing leg
trajectory and τi,ff R3is a feedforward torque, found with
τi,ff =J>Λi(Bai,ref ˙
Ji˙
qi) + Ci˙
qi+Gi(2)
where ΛiR3×3is the operational space inertia matrix,
ai,ref R3is the reference acceleration in the body frame,
qiR3is the vector of joint positions, and Ci˙
qi+Giis
the torque due to gravity and Coriolis forces for the leg.
To ensure high-gain stability in a wide range of leg
configurations, the Kpmatrix must be adjusted to keep
the natural frequency of the closed loop system relatively
constant in response to changes in the apparent mass of
the leg. The i-th diagonal entry of Kprequired to maintain
a constant natural frequency ωifor the i-th axis can be
approximated with
Kp,i =ω2
iΛi,i (3)
where Λi,i is the i, i-th entry in the mass matrix, correspond-
ing to the apparent mass of the leg along the i-th axis.
Desired footstep locations are chosen with a simple heuris-
tic described in Section V. Additionally, a contact detection
algorithm [25] detects and handles early or late contact. If an
early contact is detected, the controller immediately switches
to stance and begins ground force control.
E. Ground Force Control
During ground force control, joint torques are computed
with
τi=J>
iR>
ifi(4)
where Ris the rotation matrix which transforms from body
to world coordinates, JR3×3is the foot Jacobian, and f
is the vector of forces calculated from the model predictive
controller described in Section IV.
III. SIMPLIFIED ROBOT DYNAMICS
The predictive controller models the robot as a single rigid
body subject to forces at the contact patches. Although ig-
noring leg dynamics is a major simplification, the controller
is still able to stabilize a high-DoF system and is robust
to these multi-body effects. For the Cheetah 3 robot, this
simplification is reasonable; the mass of the legs is roughly
10% of the robot’s total mass. For each ground reaction force
fiR3, the vector from the center of mass (COM) to the
point where the force is applied is riR3. The rigid body
dynamics in world coordinates are given by
¨
p=Pn
i=1 fi
mg(5)
d
dt(Iω) =
n
X
i=1
ri×fi(6)
˙
R= [ω]×R(7)
where pR3is the robot’s position, mis the robot’s
mass, gR3is the acceleration of gravity, IR3is
the robot’s inertia tensor, ωR3is the robot’s angular
velocity, and Ris the rotation matrix which transforms from
body to world coordinates. [x]×R3×3is defined as the
skew-symmetric matrix such that [x]×y=x×yfor all
x,yR3. The nonlinear dynamics in (6) and (7) motivate
the approximations made in the following subsection to avoid
the nonconvex optimization that would otherwise be required
for model predictive control.
A. Approximated Angular Velocity Dynamics
The robot’s orientation is expressed as a vector of Z-Y-X
Euler angles [28] Θ= [φ θ ψ]|where ψis the yaw, θis
the pitch, and φis the roll. These angles correspond to a
sequence of rotations such that the transform from body to
world coordinates can be expressed as
R=Rz(ψ)Ry(θ)Rx(φ)(8)
where Rn(α)represents a positive rotation of αabout the n-
axis. The angular velocity in world coordinates can be found
from the rate of change of these angles with
ω=
cos(θ) cos(ψ)sin(ψ) 0
cos(θ) sin(ψ) cos(ψ) 0
sin(θ)0 1
˙
φ
˙
θ
˙
ψ
(9)
If the robot is not pointed vertically (cos(θ)6= 0), equation
(9) can be inverted to find
˙
φ
˙
θ
˙
ψ
=
cos(ψ)/cos(θ) sin(ψ)/cos(θ) 0
sin(ψ) cos(ψ) 0
cos(ψ) tan(θ) sin(ψ) tan(θ) 1
ω
(10)
For small values of roll and pitch (φ, θ), equation (10) can
be approximated as
˙
φ
˙
θ
˙
ψ
cos(ψ) sin(ψ) 0
sin(ψ) cos(ψ) 0
0 0 1
ω(11)
which is equivalent to
˙
φ
˙
θ
˙
ψ
R>
z(ψ)ω(12)
Note that the order in which the Euler angle rotations are
defined is important; with an alternate sequence of rotations,
the approximation will be inaccurate for reasonable robot
orientations.
Equation (6) can be approximated with:
d
dt(Iω) = I ˙ω+ω×(Iω)I ˙ω(13)
This approximation has been made in controllers such as
[13], and discards the effect of precession and nutation of the
rotating body. The ω×(Iω)term is small for bodies with
small angular velocities and does not contribute significantly
to the dynamics of the robot. The inertia tensor in the world
coordinate system can be found with
I=RBI R|(14)
which, for small roll and pitch angles, can be approximated
by
ˆ
I=Rz(ψ)BI Rz(ψ)|(15)
where BIis the inertia tensor in body coordinates.
B. Simplified Robot Dynamics
The approximated orientation dynamics and translational
dynamics can be combined into the following form:
d
dt
ˆ
Θ
ˆp
ˆω
ˆ
˙p
=
0303R>
z(ψ)03
03030313
03030303
03030303
ˆ
Θ
ˆp
ˆω
ˆ
˙p
+
03. . . 03
03. . . 03
ˆ
I1[r1]×. . . ˆ
I1[rn]×
13/m . . . 13/m
f1
.
.
.
fn
+
0
0
0
g
(16)
Equation (16) can be rewritten with an additional gravity
state to put the dynamics into the convenient state-space
form:
˙x(t) = Ac(ψ)x(t) + Bc(r1, ..., rn, ψ )u(t)(17)
where AcR13×13 and BcR13×3n. This form depends
only on yaw and footstep locations. If these can be computed
ahead of time, the dynamics become linear time-varying,
which is suitable for convex model predictive control.
IV. MOD EL PREDICTIVE CON TROL
Desired ground reaction forces are found with a discrete-
time finite-horizon model predictive controller. Because we
consider ground reaction forces instead of joint torques,
the predictive controller does not need to be aware of the
configuration or kinematics of the leg. In general, model
predictive controllers contain a model of the system to be
controlled, and on each iteration, start from the current state
and find the optimal sequence of control inputs and the cor-
responding state trajectory over the finite-length prediction
horizon, subject to constraints on the state trajectory and
the control inputs. Because this process is repeated for every
iteration, only the first timestep of the computed control input
trajectory is applied before the controller runs again and new
control inputs are computed. In this section, we consider an
MPC problem with horizon length kin the standard form
min
x,u
k1
X
i=0
||xi+1 xi+1,ref||Qi+||ui||Ri(18)
subject to xi+1 =Aixi+Biui, i = 0 . . . k 1(19)
ciCiuici, i = 0 . . . k 1(20)
Diui= 0, i = 0 . . . k 1(21)
where xiis the system state at time step i,uiis the
control input at time step i,Qiand Riare diagonal positive
semidefinite matrices of weights, Aiand Birepresent the
discrete time system dynamics, Ci,ci,and cirepresent
inequality constraints on the control input, and Diis a matrix
which selects forces corresponding with feet not in contact
with the ground at timestep i. The notation ||a||Sis used to
indicate the weighted norm a|Sa. The controller in this form
attempts to find a sequence of control inputs that will guide
the system along the trajectory xref, trading off tracking accu-
racy for control effort, while obeying constraints. In the event
that the system cannot exactly track the reference trajectory,
which is often the case due to uncontrollable dynamics
during periods of underactuation, or due to constraints, the
predictive controller finds the best solution, in the least
squares sense, over the prediction horizon. The optimization
over the horizon while taking into account future constraints
enables the predictive controller to plan ahead for periods of
flight and regulate the states of the body during a gait when
the body is always underactuated, such as bounding.
A. Force Constraints
The equality constraint in (21) is used to set all forces
from feet off the ground to zero, enforcing the desired gait.
The inequality constraint in (20) is used to set the following
six inequality constraints for each foot on the ground
fmin fzfmax (22)
µfzfxµfz(23)
µfzfyµfz(24)
These constraints limit the minimum and maximum z-force
as well as a square pyramid approximation of the friction
cone.
B. Reference Trajectory Generation
The desired robot behavior is used to construct the ref-
erence trajectory. In our application, our reference trajecto-
ries are simple and only contain non-zero xy-velocity, xy-
position, zposition, yaw, and yaw rate. All parameters are
commanded directly by the robot operator except for yaw
and xy-position, which are determined by integrating the
appropriate velocities. The other states (roll, pitch, roll rate,
pitch rate, and z-velocity) are always set to 0. The reference
trajectory is also used to determine the dynamics constraints
and future foot placement locations. In practice, the refer-
ence trajectory is short (between 0.5 and 0.3 seconds) and
recalculated often (every 0.05 to 0.03 seconds) to ensure the
simplified dynamics remain accurate if the robot is disturbed.
C. Linear Discrete Time Dynamics
For each point nin the reference trajectory, an ap-
proximate ˆ
Bc[n]R13×3nmatrix is computed from the
Bc(r1, ..., rn, ψ)matrix defined in (17) using desired values
of ψand rifrom the reference trajectory and foot place-
ment controller. Similarly, a single ˆ
AcR13×13 matrix
is computed for the entire reference trajectory using the
average value of ψduring the reference trajectory. The
Bc(r1, ..., rn, ψ)and Acmatrices are converted to a zero
order hold discrete time model using the state transition
matrix of the extended linear system:
d
dtx
u=A B
0 0 x
u(25)
This simplification allows us to express the dynamics in the
discrete time form
x[n+ 1] = ˆ
Ax[n] + ˆ
B[n]u[n](26)
The approximation in (26) is only accurate if the robot is
able to follow the reference trajectory. Large deviations from
the reference trajectory, possibly caused by external or terrain
disturbances, will result in ˆ
B[n]being inaccurate. However,
for the first time step, ˆ
B[n]is calculated from the current
robot state, and will always be correct. If, at any point, the
robot is disturbed from following the reference trajectory,
the next iteration of the MPC, which happens at most 40 ms
after the disturbance, will recompute the reference trajectory
based on the disturbed robot state, allowing it compensate
for a disturbance.
D. QP Formulation
The optimization problem in (18) is reformulated to reduce
problem size. While a solver that could take advantage
of the sparsity and structure of our problem is likely to
be the fastest solution, it was more straightforward and
sufficiently fast to ignore the structure and sparsity and
instead work on reducing the size of the problem. With a
solver that does not exploit the sparsity of the problem, the
formulation in equation (18) has a cubic time complexity
with respect to horizon length, number of states (both control
input and state trajectory), and number of constraints (both
force and dynamics), so we achieve a significant speedup
by removing the dynamics constraints and state trajectory
from the constraints and optimization variables and include
them in the cost function instead. This formulation also
allows us to eliminate trivial optimization variables that are
constrained to zero by (21) so that we are only optimizing
forces for feet which are on the ground. This is based on
the condensed formulation discussed in [29], but includes
time-varying dynamics and state reference.
The condensed formulation allows the dynamics to be
written as
X=Aqpx0+Bqp U(27)
where XR13kis the vector of all states during the
prediction horizon and UR3nk is the vector of all control
inputs during the prediction horizon.
The objective function which minimizes the weighted
least-squares deviation from the reference trajectory and the
weighted force magnitude is:
J(U) = ||Aqpx0+Bqp Uxref||L+||U||K(28)
where LR13k×13kis a diagonal matrix of weights for state
deviations, KR3nk×3nk is a diagonal matrix of weights
for force magnitude, and Uand Xare the vectors of all
control inputs and states during the prediction horizon. On
the robot, we chose an equal weighting of forces K=α13nk.
The problem can be rewritten as:
min
U
1
2U|HU +U|g(29)
s. t. cCU c(30)
where Cis the constraint matrix and
H= 2(B|
qpLBqp +K)(31)
g= 2B|
qpL(Aqp x0y)(32)
The desired ground reaction forces are then the first 3n
elements of U. Notice that HR3nk×3nk and gR3nk×1
both have no size dependence on the number of states, only
number of feet nand horizon length k.
V. RE SU LTS
TABLE I
CON TRO LL ER SE TT IN GS A ND RO B OT DATA
m43 kg
Ixx 0.41 kgm2
Iyy 2.1kgm2
Izz 2.1kgm2
µ0.6
gz9.8m/s2
τmax 250 Nm
Θweight 1
zweight 50
yaw rate weight 1
vweight 1
force weight (α)1×106
fmin 10 N
fmax 666 N
A. Experimental Setup
The proposed controller was implemented on the MIT
Cheetah 3 Robot [26] with a horizon length of one gait
cycle (0.33 to 0.5 seconds), subdivided into between 10
and 16 timesteps, depending on the gait selected. New
predictions were made at frequencies between 25 and 50
Hz, depending on the gait selected. Reference trajectories
and desired gaits were generated based on inputs from a
video game controller. Table I contains all parameters used
for the predictive controller.
The result from the optimization is used directly and
without filter in (4) to find joint torques. State estimation,
swing leg planning, and leg impedance control happen at 1
kHz.
A simple heuristic function inspired by [1] is used to plan
desired foot locations in the xy-plane of the world coordinate
system:
pdes =pref +vCoMt/2(33)
where tis the time the foot will spend on the ground,
pref is the location on the ground beneath the hip of the
robot, and vCoM is the velocity of the robot’s center of mass
projected onto the xy-plane. The state estimator is used to
determine these values for the current time step, and the
reference trajectory is used for future values. The values of
For full videos, see https://www.youtube.com/watch?v=
q6zxCvCxhic
Fig. 4. Solve time during galloping
pdes are used for both the swing leg controller and to find ri
for the predictive controller.
The robot has an onboard computer with an Intel i7
laptop processor from 2011 and runs Ubuntu Linux with a
kernel patched with CONFIG PREEMPT RT. The high level
control code, including state estimation, swing leg control,
and the dynamics calculations are implemented in MAT-
LAB/Simulink and converted into C code. The MPC setup
described in this paper is implemented in C++. The software
uses the Eigen3 linear algebra library [30] and the qpOASES
[24] quadratic programming library. The qpOASES solver
specializes in solving quadratic programs for MPC with the
online active set strategy [31] and was used to solve the
convex optimization problem. See Figure 4 for a distribution
of typical solve times.
To evaluate the predictive controller, it was tested with all
of the common gaits: standing, trotting, a flying-trot, pacing,
bounding, pronking, and galloping as well as an original 3-
legged gait.
B. Trotting
A simple trotting gait was very effective at speeds under
1.2 m/s. While trotting, the robot has no preferred direction
of travel; it can easily travel forward, backward, sideways,
and along a diagonal at speed, or even travel in straight line
while rotating around its center. Figure 5 demonstrates an ag-
gressive turn in place with rotation speeds over 150 deg/sec,
resulting in a linear foot velocity with respect to the body
of over 1 m/s while the foot is on the ground. Additionally,
the figure shows a separate aggressive acceleration test from
-1 to 1 m/s in two seconds. Our ability to achieve these
velocities on a 10 meter by 1.3 meter platform demonstrates
the agility of the robot. The trotting gait was also tested
outdoors at speeds up to 1.2 m/s, with the robot untethered.
To demonstrate robustness, the robot was driven on muddy
and sloped ground and remained stable, even when the feet
slipped in the mud.
When trotting forward at high speed, feet in swing may
collide with feet lifting off the ground, effectively limiting
our trotting gait to low speeds. The flying-trot adds a flight
period, improving the top speed to 1.7 m/s, and allows the
robot to spin in place at 180 deg/s.
C. Disturbances and Stairs
To test the disturbance rejection of the controller, the
robot was firmly kicked while trotting. The kick was forceful
enough to accelerate the robot’s body over 1 m/s sideways,
but the robot was able to recover while keeping roll and pitch
within 10 degrees of level, as shown in Figure 7.
The flying trot gait was also tested on a staircase with
4 full size steps, which it was able to climb reliably.
Approximately 15 pieces of wood simulating debris were
scattered on the staircase to intentionally make the robot’s
feet slip. The swing trajectory height was increased to allow
the feet to reach the next step, but the robot otherwise had
no knowledge of the staircase. Contact detection algorithms
[25] allowed the gait to be modified in real time as the feet
touched down earlier or later than anticipated. We attempted
to climb and descend the debris covered staircase 3 times.
On the first attempt, the robot’s front feet reached the top,
but the operator mistakenly commanded a yaw rate of 120
deg/sec, causing a foot to step off the staircase, at which point
the robot was shut off. The second attempt was successful at
climbing and descending the stairs. In the third attempt, the
robot again reached the top step and had a rear foot step off
the staircase, causing the knee to invert. The robot slipped
down a few stairs and regained control with its front feet on
the first step. The operator commanded the robot to correct
the orientation of the knee and tried again. This time, the
robot was successful in ascending the stairs, but on the way
down, as the front feet were about to step off the staircase,
the robot kicked its own power switch and shut off. To the
best of our knowledge, this is the first time a legged robot
has climbed a staircase while using a dynamic gait with a
flight period.
D. Pronking/Jumping
To demonstrate the robustness of our controller, we tested
a pronking gait, which is a sequence of short jumps approx-
imately 15 cm high. The robot spends 150 ms with all four
feet on the ground, followed by 350 ms of flight. The robot is
able to land and stabilize itself during the 150 ms of ground
contact, allowing it to pronk in place indefinitely.
Fig. 5. Turning while trotting in place and separate acceleration test
Fig. 6. Orientation control during 2.25 m/s bounding
Fig. 7. Velocity and Orientation when the robot is kicked
Fig. 8. Leg data during 2.5 m/s galloping
E. Bounding and Galloping
Bounding on Cheetah 3 is able to achieve higher speeds
than trotting due to the higher gait frequency (3.3 Hz) and
longer flight times. When bounding with low flight times,
the legs must be narrowed in the front so that the rear feet
can swing past. For our bounding gait, each foot is on the
ground for 90 ms and in swing for 210 ms. While bounding,
the robot was able to rotate in place at speeds up to 180
deg/sec. To demonstrate the stability of the controller, the
spacing between the left and right feet was decreased until
the robot fell. The robot was able to bound with the feet 10
cm apart indefinitely. With the feet 5 cm apart from each
other, the robot was able to bound, but had poor control of
sideways velocity, limiting the test to roughly 10 footsteps.
Figure 6 shows the orientation during 2.25 m/s bounding.
Bounding was tested up to 2.5 m/s and likely can go faster,
however, galloping was observed to be much smoother, so
it was used for all high speed tests. Galloping was able
to reach a maximum speed of 3 m/s, at which point it
became challenging to keep the robot on the treadmill. Figure
10 shows accurate velocity tracking of galloping up to the
maximum speed, and Figures 8 and 9 show leg and controller
data during 2.5 m/s galloping.
Fig. 9. Commanded forces and estimated orientation during 2.5 m/s
galloping
Fig. 10. Velocity control of galloping to 3 m/s
F. Limitations at High Speed
The MIT Cheetah 3 robot was developed with the intent
to operate efficiently, carrying payloads indoors and near
humans. As a result, its actuators and legs are designed for
lower speeds than Cheetah 2, limiting the linear velocity
of the feet. When testing high speed locomotion, the legs
installed on Cheetah 3 had a maximum velocity of 15
rad/sec, significantly slower than the maximum of 24 rad/sec,
observed on Cheetah 2. When operating near the hip velocity
limit, the swing leg controller does not track well. In our
attempts to go faster than 3 m/s, the legs could not swing
far enough forward in time, causing the robot’s orientation
control to become less accurate. The robot was able to handle
the increased roll and pitch error, but it became challenging
to keep the robot on the 1.3 meter wide treadmill due to
drift in yaw velocity. All of our high speed tests ended
either with the robot accidentally being driven off the side of
the treadmill or with a mechanical failure of the robot. We
suspect that with increased leg velocity, higher speeds can
be reached. In our full, multi-body simulation of the robot,
we have achieved speeds up to 6 m/s when we increase leg
velocity to a maximum of 30 rad/sec.
VI. CONCLUSIONS AND FUTURE WORK
Despite significant simplifications to the robot dynamics
model, the controller is shown to have good performance
with a variety of gaits. We believe our controller is success-
ful because our approximate model still captures many of
the important details of locomotion, including the ground
reaction force constraints. We find that a highly accurate
model of the robot’s dynamics during the prediction horizon
is less important than an accurate model of the robot’s
instantaneous dynamics. Our approach updates the dynamics
during the prediction horizon frequently and with minimal
delay, ensuring the instantaneous approximation is always
accurate. Between iterations of our control algorithm, a linear
approximation of dynamics appears to be sufficient.
In the future, we plan to more thoroughly investigate
different gaits and aggressive behaviors. It is very likely
that higher speeds and greater stability can be achieved by
designing a more favorable gait. So far, all of the gaits
used with the proposed controller were created manually,
and imitated gaits found in dogs and other legged robots.
We plan to replace these predetermined gaits with contact
patterns determined by a higher level planner to improve
the robustness and performance of our locomotion. This
framework would allow the higher-level planner to run
slowly and the low-level predictive controller can continue
to run rapidly.
REFERENCES
[1] M. H. Raibert, Legged Robots That Balance. Cambridge, MA, USA:
Massachusetts Institute of Technology, 1986.
[2] H.-W. Park, P. M. Wensing, and S. Kim, “High-speed bounding with
the mit cheetah 2: Control design and experiments,” The International
Journal of Robotics Research, vol. 36, no. 2, pp. 167–192, 2017.
[3] D. P. Krasny and D. E. Orin, “Evolution of a 3d gallop in a
quadrupedal model with biological characteristics,” Journal of Intelli-
gent & Robotic Systems, vol. 60, no. 1, pp. 59–82, 2010.
[4] R. Orsolino, M. Focchi, D. G. Caldwell, and C. Semini, “A combined
limit cycle - zero moment point based approach for omni-directional
quadrupedal bounding,” in International Conference on Climbing and
Walking Robots (CLAWAR), 2017.
[5] C. Gehring, S. Coros, M. Hutler, C. D. Bellicoso, H. Heijnen, R. Di-
ethelm, M. Bloesch, P. Fankhauser, J. Hwangbo, M. Hoepflinger, and
R. Siegwart, “Practice makes perfect: An optimization-based approach
to controlling agile motions for a quadruped robot,” IEEE Robotics
Automation Magazine, vol. 23, no. 1, pp. 34–43, March 2016.
[6] M. Rutschmann, B. Satzinger, M. Byl, and K. Byl, “Nonlinear model
predictive control for rough-terrain robot hopping,” in 2012 IEEE/RSJ
International Conference on Intelligent Robots and Systems, Oct 2012,
pp. 1859–1864.
[7] J. Koenemann, A. D. Prete, Y. Tassa, E. Todorov, O. Stasse, M. Ben-
newitz, and N. Mansard, “Whole-body model-predictive control ap-
plied to the hrp-2 humanoid,” in 2015 IEEE/RSJ International Confer-
ence on Intelligent Robots and Systems (IROS), Sept 2015, pp. 3346–
3351.
[8] Y. Tassa, T. Erez, and E. Todorov, “Synthesis and stabilization of
complex behaviors through online trajectory optimization,” in 2012
IEEE/RSJ International Conference on Intelligent Robots and Systems,
Oct 2012, pp. 4906–4913.
[9] G. Bledt, P. M. Wensing, and S. Kim, “Policy-regularized model
predictive control to stabilize diverse quadrupedal gaits for the mit
cheetah,” in 2017 IEEE International Conference on Intelligent Robots
and Systems, 2017.
[10] A. W. Winkler, D. C. Bellicoso, M. Hutter, and J. Buchli, “Gait
and trajectory optimization for legged systems through phase-based
end-effector parameterization,IEEE Robotics and Automation Letters
(RA-L), may 2018.
[11] A. W. Winkler, F. Farshidian, D. Pardo, M. Neunert, and J. Buchli,
“Fast trajectory optimization for legged robots using vertex-based zmp
constraints,” IEEE Robotics and Automation Letters (RA-L), vol. 2, pp.
2201–2208, oct 2017.
[12] M. Neunert, M. St¨
auble, M. Giftthaler, C. D. Bellicoso, J. Carius,
C. Gehring, M. Hutter, and J. Buchli, “Whole-Body Nonlinear Model
Predictive Control Through Contacts for Quadrupeds,ArXiv e-prints,
Dec. 2017.
[13] M. Focchi, A. del Prete, I. Havoutis, R. Featherstone, D. G. Caldwell,
and C. Semini, “High-slope terrain locomotion for torque-controlled
quadruped robots,” Autonomous Robots, vol. 41, no. 1, pp. 259–272,
Jan 2017.
[14] Y. Abe, M. da Silva, and J. Popovi´
c, “Multiobjective control
with frictional contacts,” in Proceedings of the 2007 ACM SIG-
GRAPH/Eurographics Symposium on Computer Animation, ser. SCA
’07. Aire-la-Ville, Switzerland, Switzerland: Eurographics Associa-
tion, 2007, pp. 249–258.
[15] B. J. Stephens and C. G. Atkeson, “Push recovery by stepping for
humanoid robots with force controlled joints,” in 2010 10th IEEE-
RAS International Conference on Humanoid Robots, Dec 2010, pp.
52–59.
[16] A. Ruina, J. E. Bertram, and M. Srinivasan, “A collisional model of the
energetic cost of support work qualitatively explains leg sequencing
in walking and galloping, pseudo-elastic leg behavior in running and
the walk-to-run transition,” Journal of theoretical biology, vol. 237,
no. 2, pp. 170–192, 2005.
[17] R. M. Walter and D. R. Carrier, “Rapid acceleration in dogs: ground
forces and body posture dynamics,” Journal of Experimental Biology,
vol. 212, no. 12, pp. 1930–1939, 2009.
[18] J. A. Smith and I. Poulakakis, “Rotary gallop in the unteth-
ered quadrupedal robot scout ii,” in 2004 IEEE/RSJ International
Conference on Intelligent Robots and Systems (IROS) (IEEE Cat.
No.04CH37566), vol. 3, Sept 2004, pp. 2556–2561 vol.3.
[19] H.-W. Park and S. Kim, “Quadrupedal galloping control for a wide
range of speed via vertical impulse scaling,” Bioinspiration and
Biomimetics, vol. 10, no. 2, p. 025003, 2015.
[20] “Introducing WildCat, https://www.youtube.com/watch?v=
wE3fmFTtP9g, Oct 2013.
[21] S. Boyd and L. Vandenberghe, Convex optimization. Cambridge
university press, 2004.
[22] Y. Wang and S. Boyd, “Fast model predictive control using online
optimization,” IEEE Transactions on Control Systems Technology,
vol. 18, no. 2, pp. 267–278, March 2010.
[23] A. Domahidi, E. Chu, and S. Boyd, “ECOS: An SOCP solver for
embedded systems,” in European Control Conference (ECC), 2013,
pp. 3071–3076.
[24] H. Ferreau, C. Kirches, A. Potschka, H. Bock, and M. Diehl,
“qpOASES: A parametric active-set algorithm for quadratic program-
ming,” Mathematical Programming Computation, vol. 6, no. 4, pp.
327–363, 2014.
[25] G. Bledt, P. M. Wensing, S. Ingersoll, and S. Kim, “Contact model
fusion for event-based locomotion in unstructured terrains,” in 2018
IEEE International Conference on Robotics and Automation, 2018.
[26] G. Bledt, M. J. Powell, B. Katz, J. Di Carlo, P. M. Wensing, and
S. Kim, “Mit cheetah 3: Design and control of a robust, dynamics
quadruped robot,” in 2018 IEEE International Conference on Intelli-
gent Robots and Systems, 2018.
[27] P. M. Wensing, A. Wang, S. Seok, D. Otten, J. Lang, and S. Kim,
“Proprioceptive actuator design in the mit cheetah: Impact mitigation
and high-bandwidth physical interaction for dynamic legged robots,”
IEEE Transactions on Robotics, vol. 33, no. 3, pp. 509–522, June
2017.
[28] J. Craig, Introduction to Robotics: Mechanics and Control, ser.
Addison-Wesley series in electrical and computer engineering: control
engineering. Pearson/Prentice Hall, 2005.
[29] J. L. Jerez, E. C. Kerrigan, and G. A. Constantinides, “A condensed
and sparse qp formulation for predictive control,” in 2011 50th
IEEE Conference on Decision and Control and European Control
Conference, Dec 2011, pp. 5217–5222.
[30] G. Guennebaud, B. Jacob et al., “Eigen v3,” http://eigen.tuxfamily.org,
2010.
[31] H. Ferreau, H. Bock, and M. Diehl, “An online active set strategy
to overcome the limitations of explicit mpc,International Journal of
Robust and Nonlinear Control, vol. 18, no. 8, pp. 816–830, 2008.
... Equations (26)- (29) are solved simultaneously to obtain the force in y and z directions at the heel and tip of the foot, as shown in Equation (30). ...
... Because according to the PD control law, this paper focuses on the end force F swing of the swing leg, and calculates F swing according to the deviation of the speed of the swing leg end and the deviation of the position. Equation (46) calculates the expectation of the end position using the method from Carlo [30]. ...
... Because according to the PD control law, this paper focuses on the end force of the swing leg, and calculates according to the deviation of the speed of the swing leg end and the deviation of the position. Equation (46) calculates the expectation of the end position using the method from Carlo [30]. ...
Article
Full-text available
For a forward-bending biped robot with 10 degrees of freedom on its legs, a new control framework of MPC-DCM based on force and moment is proposed in this paper. Specifically, the Diverging Component of Motion (DCM) is a stability criterion for biped robots based on linear inverted pendulum, and Model Predictive Control (MPC) is an optimization solution strategy using rolling optimization. In this paper, DCM theory is applied to the state transition matrix of the system, combined with simplified rigid body dynamics, the mathematical description of the biped robot system is established, the classical MPC method is used to optimize the control input, and DCM constraints are added to the constraints of MPC, making the real-time DCM approximate to a straight line in the walking single gait. At the same time, the linear angle and friction cone constraints are considered to enhance the stability of the robot during walking. In this paper, MATLAB/Simulink is used to simulate the robot. Under the control of this algorithm, the robot can reach a walking speed of 0.75 m/s and has a certain anti-disturbance ability and ground adaptability. In this paper, the Model-H16 robot is used to deploy the physical algorithm, and the linear walking and obstacle walking of the physical robot are realized.
... While several works study transitions between such gaits (for example), the optimal transition times, speeds, and between which discrete gaits remains an open question. Additionally, for frameworks that do show transitions between gaits, the parameters must often be re-tuned for each (MPC) [16], may have heuristics for transitioning [17], or may otherwise be non-optimal, as the cyclic motions may affect the body and joints differently. For example, in contrast with most robots (with some exceptions [18], [19]), animals do not bound with a rigid spine. ...
... For quadruped robots, gaits can be encoded in a biological neural network (CPG) [8], [20]- [22], enforced through a fixed pattern in optimal control frameworks [16], [23], [24], specifically rewarded in learning frameworks through a reward function [25], [26], or can emerge naturally during the training process [27]- [29]. One observation is that learned controllers working at a wide range of speeds seem to converge to trot gaits, especially when the reward function has terms penalizing non-stable motions, as the trot gait minimizes body angular velocities even at high speeds [30], [31]. ...
... While several common quadrupedal gaits have been successfully demonstrated on quadruped hardware, previous work requires either explicit parameter tuning in MPC [16], extensive reward function tuning [17], [25], specific training schemes [29], or expert demonstrations from animals or MPC to imitate [34]. In contrast, we show all quadruped gaits and their transitions can be realized without reward function tuning or any expert demonstrations. ...
Preprint
We present a framework for learning a single policy capable of producing all quadruped gaits and transitions. The framework consists of a policy trained with deep reinforcement learning (DRL) to modulate the parameters of a system of abstract oscillators (i.e. Central Pattern Generator), whose output is mapped to joint commands through a pattern formation layer that sets the gait style, i.e. body height, swing foot ground clearance height, and foot offset. Different gaits are formed by changing the coupling between different oscillators, which can be instantaneously selected at any velocity by a user. With this framework, we systematically investigate which gait should be used at which velocity, and when gait transitions should occur from a Cost of Transport (COT), i.e. energy-efficiency, point of view. Additionally, we note how gait style changes as a function of locomotion speed for each gait to keep the most energy-efficient locomotion. While the currently most popular gait (trot) does not result in the lowest COT, we find that considering different co-dependent metrics such as mean base velocity and joint acceleration result in different `optimal' gaits than those that minimize COT. We deploy our controller in various hardware experiments, showing all 9 typical quadruped animal gaits, and demonstrate generalizability to unseen gaits during training, and robustness to leg failures. Video results can be found at https://youtu.be/OLoWSX_R868.
... As discussed in Sec. I, we explore solving this problem via model predictive control (MPC) motivated by recent successes [13]- [15]. We choose actions to be desired joint accelerationsθ t , integrated to obtain desired joint velocity and positionθ t , θ t targets respectively. ...
... MPC has a rich history in feedback control of complex robotic systems under dynamic constraints [13]- [15]. Instead of searching for a global policy, MPC optimizes local policies online at a given state x r t using an approximate model (M ) with a finite lookahead horizon H, by minimizing a model-based approximation of the value function VM ( ...
Preprint
We investigate the problem of teaching a robot manipulator to perform dynamic non-prehensile object transport, also known as the `robot waiter' task, from a limited set of real-world demonstrations. We propose an approach that combines batch reinforcement learning (RL) with model-predictive control (MPC) by pretraining an ensemble of value functions from demonstration data, and utilizing them online within an uncertainty-aware MPC scheme to ensure robustness to limited data coverage. Our approach is straightforward to integrate with off-the-shelf MPC frameworks and enables learning solely from task space demonstrations with sparsely labeled transitions, while leveraging MPC to ensure smooth joint space motions and constraint satisfaction. We validate the proposed approach through extensive simulated and real-world experiments on a Franka Panda robot performing the robot waiter task and demonstrate robust deployment of value functions learned from 50-100 demonstrations. Furthermore, our approach enables generalization to novel objects not seen during training and can improve upon suboptimal demonstrations. We believe that such a framework can reduce the burden of providing extensive demonstrations and facilitate rapid training of robot manipulators to perform non-prehensile manipulation tasks. Project videos and supplementary material can be found at: https://sites.google.com/view/cvmpc.
... The path planner decides the route to take attempting to avoid any obstacles within the area to reach the objective. This route can be used to develop a feasible footstep plan and subsequently obtain the CoM motion for the WBC The CoM planner can be composed in a variety of ways using methods such as Model Predictive Control (MPC) [64], Linear Inverted Pendulum (LIP) dynamics [26], and the Divergent Component of Motion (DCM) [65], [35]. Some planners do not require precise footstep locations and rely on well tuned heuristics [66], [64], but this can lead to stability challenges if terrains are too rough [67]. ...
... This route can be used to develop a feasible footstep plan and subsequently obtain the CoM motion for the WBC The CoM planner can be composed in a variety of ways using methods such as Model Predictive Control (MPC) [64], Linear Inverted Pendulum (LIP) dynamics [26], and the Divergent Component of Motion (DCM) [65], [35]. Some planners do not require precise footstep locations and rely on well tuned heuristics [66], [64], but this can lead to stability challenges if terrains are too rough [67]. PANDORA utilizes the DCM approach which indirectly stabilizes the CoM based on the DCM coordinate definition [68]. ...
Preprint
Full-text available
In this work, the joint-control strategy is presented for the humanoid robot, PANDORA, whose structural components are designed to be compliant. As opposed to contemporary approaches which design the elasticity internal to the actuator housing, PANDORA's structural components are designed to be compliant under load or, in other words, structurally elastic. To maintain the rapid design benefit of additive manufacturing, this joint control strategy employs a disturbance observer (DOB) modeled from an ideal elastic actuator. This robust controller treats the model variation from the structurally elastic components as a disturbance and eliminates the need for system identification of the 3D printed parts. This enables mechanical design engineers to iterate on the 3D printed linkages without requiring consistent tuning from the joint controller. Two sets of hardware results are presented for validating the controller. The first set of results are conducted on an ideal elastic actuator testbed that drives an unmodeled, 1 DoF weighted pendulum with a 10 kg mass. The results support the claim that the DOB can handle significant model variation. The second set of results is from a robust balancing experiment conducted on the 12 DoF lower body of PANDORA. The robot maintains balance while an operator applies 50 N pushes to the pelvis, where the actuator tracking results are presented for the left leg.
... Using these three relations we can obtain the following: [10 −4 , 10 −3 , 10 −2 , 10 −1 , 1, 2, 3,4,5,6,7,8,9,10,25,50, 100] k [10 3 , 10 4 , 10 5 , 10 6 , 10 7 , 10 8 , 10 9 , 10 10 ] p [5,6,7,8,9,10] ...
Preprint
Full-text available
Generating optimal trajectories for high-dimensional robotic systems in a time-efficient manner while adhering to constraints is a challenging task. To address this challenge, this paper introduces PHLAME, which applies pseudospectral collocation and spatial vector algebra to efficiently solve the Affine Geometric Heat Flow (AGHF) Partial Differential Equation (PDE) for trajectory optimization. Unlike traditional PDE approaches like the Hamilton-Jacobi-Bellman (HJB) PDE, which solve for a function over the entire state space, computing a solution to the AGHF PDE scales more efficiently because its solution is defined over a two-dimensional domain, thereby avoiding the intractability of state-space scaling. To solve the AGHF one usually applies the Method of Lines (MOL), which works by discretizing one variable of the AGHF PDE, effectively converting the PDE into a system of ordinary differential equations (ODEs) that can be solved using standard time-integration methods. Though powerful, this method requires a fine discretization to generate accurate solutions and still requires evaluating the AGHF PDE which can be computationally expensive for high-dimensional systems. PHLAME overcomes this deficiency by using a pseudospectral method, which reduces the number of function evaluations required to yield a high accuracy solution thereby allowing it to scale efficiently to high-dimensional robotic systems. To further increase computational speed, this paper presents analytical expressions for the AGHF and its Jacobian, both of which can be computed efficiently using rigid body dynamics algorithms. The proposed method PHLAME is tested across various dynamical systems, with and without obstacles and compared to a number of state-of-the-art techniques. PHLAME generates trajectories for a 44-dimensional state-space system in 3\sim3 seconds, much faster than current state-of-the-art techniques.
... Additionally, maintaining stability and smooth operation at high speeds or during dynamic maneuvers remains a challenge [5]. For example, the MIT Cheetah robot, known for its speed and agility, struggles to maintain balance and stability when transitioning between different terrains or executing rapid maneuvers [6]. This instability stems from the lack of integration between high-frequency sensor feedback and low-latency control algorithms necessary for real-time adjustments [7]. ...
Article
Full-text available
This article delineates the enhancement of an autonomous navigation and obstacle avoidance system for a quadruped robot dog. Part one of this paper presents the integration of a sophisticated multi-level dynamic control framework, utilizing Model Predictive Control (MPC) and Whole-Body Control (WBC) from MIT Cheetah. The system employs an Intel RealSense D435i depth camera for depth vision-based navigation, which enables high-fidelity 3D environmental mapping and real-time path planning. A significant innovation is the customization of the EGO-Planner to optimize trajectory planning in dynamically changing terrains, coupled with the implementation of a multi-body dynamics model that significantly improves the robot’s stability and maneuverability across various surfaces. The experimental results show that the RGB-D system exhibits superior velocity stability and trajectory accuracy to the SLAM system, with a 20% reduction in the cumulative velocity error and a 10% improvement in path tracking precision. The experimental results also show that the RGB-D system achieves smoother navigation, requiring 15% fewer iterations for path planning, and a 30% faster success rate recovery in challenging environments. The successful application of these technologies in simulated urban disaster scenarios suggests promising future applications in emergency response and complex urban environments. Part two of this paper presents the development of a robust path planning algorithm for a robot dog on a rough terrain based on attached binocular vision navigation. We use a commercial-of-the-shelf (COTS) robot dog. An optical CCD binocular vision dynamic tracking system is used to provide environment information. Likewise, the pose and posture of the robot dog are obtained from the robot’s own sensors, and a kinematics model is established. Then, a binocular vision tracking method is developed to determine the optimal path, provide a proposal (commands to actuators) of the position and posture of the bionic robot, and achieve stable motion on tough terrains. The terrain is assumed to be a gentle uneven terrain to begin with and subsequently proceeds to a more rough surface. This work consists of four steps: (1) pose and position data are acquired from the robot dog’s own inertial sensors, (2) terrain and environment information is input from onboard cameras, (3) information is fused (integrated), and (4) path planning and motion control proposals are made. Ultimately, this work provides a robust framework for future developments in the vision-based navigation and control of quadruped robots, offering potential solutions for navigating complex and dynamic terrains.
... MPC enables a system to make current decisions while considering their impact on the future through predictive modeling 14 , which has shown promise in recent research on legged locomotion. Recently, some complex leg models, such as single rigid-body models 15,16 , central dynamics models 17,18 , and whole-body models 19 , have been used to improve the locomotor skills of legged robots, especially quadruped robots. These MPC-based strategies focus on the unified processing of legged motions and can find reliable motion trajectories in real time, which are robust to external disturbances. ...
Article
Full-text available
Agile and adaptive maneuvers such as fall recovery, high-speed turning, and sprinting in the wild are challenging for legged systems. We propose a Curricular Hindsight Reinforcement Learning (CHRL) that learns an end-to-end tracking controller that achieves powerful agility and adaptation for the legged robot. The two key components are (i) a novel automatic curriculum strategy on task difficulty and (ii) a Hindsight Experience Replay strategy adapted to legged locomotion tasks. We demonstrated successful agile and adaptive locomotion on a real quadruped robot that performed fall recovery autonomously, coherent trotting, sustained outdoor running speeds up to 3.45 m/s, and a maximum yaw rate of 3.2 rad/s. This system produces adaptive behaviors responding to changing situations and unexpected disturbances on natural terrains like grass and dirt.
... Legged robots are also becoming a viable solution for the exploration of extreme environments due to their increased ability to climb and overcome obstacles. Recent quadrupeds (Di Carlo et al., 2018) and biped robots (Komizunai et al., 2010) usually employ spherical or flat appendices as feet, which provides stability even on softer terrain (Yang et al., 2024). Planetary exploration robots (Parness et al., 2017;Uno et al., 2021) are often equipped with spine grippers to grasp the rough surface of rocks, allowing them to descend into lunar caves. ...
Preprint
Full-text available
Wheeled rovers have been the primary choice for lunar exploration due to their speed and efficiency. However, deeper areas, such as lunar caves and craters, require the mobility of legged robots. To do so, appropriate end effectors must be designed to enable climbing and walking on the granular surface of the Moon. This paper investigates the behavior of an underactuated soft gripper on deformable granular material when a legged robot is walking in soft soil. A modular test bench and a simulation model were developed to observe the gripper sinkage behavior under load. The gripper uses tendon-driven fingers to match its target shape and grasp on the target surface using multiple micro-spines. The sinkage of the gripper in silica sand was measured by comparing the axial displacement of the gripper with the nominal load of the robot mass. Multiple experiments were performed to observe the sinkage of the gripper over a range of slope angles. A simulation model accounting for the degrees of compliance of the gripper fingers was created using Altair MotionSolve software and coupled to Altair EDEM to compute the gripper interaction with particles utilizing the discrete element method. After validation of the model, complementary simulations using Lunar gravity and a regolith particle model were performed. The results show that a satisfactory gripper model with accurate freedom of motion can be created in simulation using the Altair simulation packages and expected sinkage under load in a particle-filled environment can be estimated using this model. By computing the sinkage of the end effector of legged robots, the results can be directly integrated into the motion control algorithm and improve the accuracy of mobility in a granular material environment.
Preprint
Full-text available
As legged robots take on roles in industrial and autonomous construction, collaborative loco-manipulation is crucial for handling large and heavy objects that exceed the capabilities of a single robot. However, ensuring the safety of these multi-robot tasks is essential to prevent accidents and guarantee reliable operation. This paper presents a hierarchical control system for object manipulation using a team of quadrupedal robots. The combination of the motion planner and the decentralized locomotion controller in a hierarchical structure enables safe, adaptive planning for teams in complex scenarios. A high-level nonlinear model predictive control planner generates collision-free paths by incorporating control barrier functions, accounting for static and dynamic obstacles. This process involves calculating contact points and forces while adapting to unknown objects and terrain properties. The decentralized loco-manipulation controller then ensures each robot maintains stable locomotion and manipulation based on the planner's guidance. The effectiveness of our method is carefully examined in simulations under various conditions and validated in real-life setups with robot hardware. By modifying the object's configuration, the robot team can maneuver unknown objects through an environment containing both static and dynamic obstacles. We have made our code publicly available in an open-source repository at \url{https://github.com/DRCL-USC/collaborative_loco_manipulation}.
Article
Full-text available
As legged robots are sent into unstructured environments, the ability to robustly manage contact transitions will be a critical skill. This paper introduces an approach to probabilistically fuse contact models, managing uncertainty in terrain geometry, dynamic modeling, and kinematics to improve the robustness of contact initiation at touchdown. A discrete-time extension of the generalized-momentum disturbance observer is presented to increase the accuracy of proprioceptive force control estimates. This information is fused with other contact priors under a framework of Kalman Filtering to increase robustness of the method. This approach results in accurate contact detection with 99.3 % accuracy and a small 4-5ms delay. Using this new detector, an Event-Based Finite State Machine is implemented to deal with unexpected early and late contacts. This allows the robot to traverse cluttered environments by modifying the control actions for each individual leg based on the estimated contact state rather than adhering to a rigid time schedule regardless of actual contact state. Experiments with the MIT Cheetah 3 robot show the success of both the detection algorithm, as well as the Event-Based FSM while making unexpected contacts during trotting.
Article
Full-text available
We present a single Trajectory Optimization formulation for legged locomotion that automatically determines the gait-sequence, step-timings, footholds, swing-leg motions and 6D body motion over non-flat terrain, without any additional modules. Our phase-based parameterization of feet motion and forces allows to optimize over the discrete gait sequence using only continuous decision variables. The system is represented using a simplified Centroidal dynamics model that is influenced by the feet’s location and forces. We explicitly enforce friction cone constraints, depending on the shape of the terrain. The NLP solver generates highly dynamic motion-plans with full flight-phases for a variety of legged systems with arbitrary morphologies in an efficient manner. We validate the feasibility of the generated plans in simulation and on the real quadruped robot ANYmal. Additionally, the entire solver software TOWR used to generate these motions is made freely available
Article
Full-text available
This paper combines the fast Zero-Moment-Point (ZMP) approaches that work well in practice with the broader range of capabilities of a Trajectory Optimization formulation, by optimizing over body motion, footholds and Center of Pressure simultaneously. We introduce a vertex-based representation of the support-area constraint, which can treat arbitrarily oriented point-, line-, and area-contacts uniformly. This generalization allows us to create motions such quadrupedal walking, trotting, bounding, pacing, combinations and transitions between these, limping, bipedal walking and push-recovery all with the same approach. This formulation constitutes a minimal representation of the physical laws (unilateral contact forces) and kinematic restrictions (range of motion) in legged locomotion, which allows us to generate various motion in less than a second. We demonstrate the feasibility of the generated motions on a real quadruped robot.
Article
Full-text available
This paper presents the design and implementation of a bounding controller for the MIT Cheetah 2 and its experimental results. The paper introduces the architecture of the controller along with the functional roles of its subcomponents. The application of impulse scaling provides feedforward force profiles that automatically adapt across a wide range of speeds. A discrete gait pattern stabilizer maintains the footfall sequence and timing. Continuous feedback is layered to manage balance during the stance phase. Stable hybrid limit cycles are exhibited in simulation using simplified models, and are further validated in untethered three-dimensional bounding experiments. Experiments are conducted both indoors and outdoors on various man-made and natural terrains. The control framework is shown to provide stable bounding in the hardware, at speeds of up to 6.4 m/s and with a minimum total cost of transport of 0.47. These results are unprecedented accomplishments in terms of efficiency and speed in untethered experimental quadruped machines.
Article
Full-text available
Designing an actuator system for highly dynamic legged robots has been one of the grand challenges in robotics research. Conventional actuators for manufacturing applications have difficulty satisfying design requirements for high-speed locomotion, such as the need for high torque density and the ability to manage dynamic physical interactions. To address this challenge, this paper suggests a proprioceptive actuation paradigm that enables highly dynamic performance in legged machines. Proprioceptive actuation uses collocated force control at the joints to effectively control contact interactions at the feet under dynamic conditions. Modal analysis of a reduced leg model and dimensional analysis of DC motors address the main principles for implementation of this paradigm. In the realm of legged machines, this paradigm provides a unique combination of high torque density, high-bandwidth force control, and the ability to mitigate impacts through backdrivability. We introduce a new metric named the “impact mitigation factor” (IMF) to quantify backdrivability at impact, which enables design comparison across a wide class of robots. The MIT Cheetah leg is presented, and is shown to have an IMF that is comparable to other quadrupeds with series springs to handle impact. The design enables the Cheetah to control contact forces during dynamic bounding, with contact times down to 85 ms and peak forces over 450 N. The unique capabilities of the MIT Cheetah, achieving impact-robust force-controlled operation in high-speed three-dimensional running and jumping, suggest wider implementation of this holistic actuation approach.
Conference Paper
This paper introduces a new robust, dynamic quadruped, the MIT Cheetah 3. Like its predecessor, the Cheetah 3 exploits tailored mechanical design to enable simple control strategies for dynamic locomotion and features high-bandwidth proprioceptive actuators to manage physical interaction with the environment. A new leg design is presented that includes proprioceptive actuation on the abduction/adduction degrees of freedom in addition to an expanded range of motion on the hips and knees. To make full use of these new capabilities, general balance and locomotion controllers for Cheetah 3 are presented. These controllers are embedded into a modular control architecture that allows the robot to handle unexpected terrain disturbances through reactive gait modification and without the need for external sensors or prior environment knowledge. The efficiency of the robot is demonstrated by a low Cost of Transport (CoT) over multiple gaits at moderate speeds, with the lowest CoT of 0.45 found during trotting. Experiments showcase the ability to blindly climb up stairs as a result of the full system integration. These results collectively represent a promising step toward a platform capable of generalized dynamic legged locomotion.
Conference Paper
As legged robots are sent into unstructured environments , the ability to robustly manage contact transitions will be a critical skill. This paper introduces an approach to probabilistically fuse contact models, managing uncertainty in terrain geometry, dynamic modeling, and kinematics to improve the robustness of contact initiation at touchdown. A discrete-time extension of the generalized-momentum disturbance observer is presented to increase the accuracy of proprioceptive force control estimates. This information is fused with other contact priors under a framework of Kalman Filtering to increase robustness of the method. This approach results in accurate contact detection with 99.3% accuracy and a small 4 − 5ms delay. Using this new detector, an Event-Based Finite State Machine is implemented to deal with unexpected early and late contacts. This allows the robot to traverse cluttered environments by modifying the control actions for each individual leg based on the estimated contact state rather than adhering to a rigid time schedule regardless of actual contact state. Experiments with the MIT Cheetah 3 robot show the success of both the detection algorithm, as well as the Event-Based FSM while making unexpected contacts during trotting.
Article
This work approaches the problem of controlling quadrupedal running and jumping motions with a parametrized, model-based, state-feedback controller. Inspired by the motor learning principles observed in nature, our method automatically fine tunes the parameters of our controller by repeatedly executing slight variations of the same motion task. This learn-through-practice process is performed in simulation in order to best exploit computational resources and to prevent the robot from damaging itself. In order to ensure that the simulation results match the behavior of the hardware platform sufficiently well, we introduce and validate an accurate model of the compliant actuation system. The proposed method is experimentally verified on the torque-controllable quadruped robot StarlETH by executing squat jumps and dynamic gaits such as a running trot, pronk and a bounding gait.