Soft Bilinear Inverted Pendulum: a Model to Enable Locomotion with Soft Contacts

Davide De Benedittis *

University of Pisa

Franco Angelini

University of Pisa

Manolo Garabini

University of Pisa

IEEE Transactions on Systems, Man, and Cybernetics: Systems

*Corresponding author: davide.debenedittis@phd.unipi.it

Abstract

The robotics research community has developed several effective techniques for quadrupedal locomotion. Most of these methods ease the modeling and control problem by assuming a rigid contact between the feet and the terrain. However, in the case of compliant terrain or robots equipped with soft feet, this assumption no longer holds, as the contact point moves and the reaction forces experience a delay. This paper presents a novel approach for quadrupedal locomotion in the presence of soft contacts. The control architecture consists of two blocks: upstream, the Motion Planner (MP) computes a feasible trajectory using Model Predictive Control (MPC); downstream, the Tracking Controller (TC) employs Hierarchical Optimization (HO) to achieve motion tracking. This choice allows the control architecture to employ a large time horizon without heavily compromising the model’s accuracy. For the first time, both blocks consider the contact compliance: in the MP, the classic Linear Inverted Pendulum model is extended by proposing the Soft Bilinear Inverted Pendulum (SBIP) model; conversely, the Tracking Controller (TC) is a Whole-Body Controller (WBC) that considers the full dynamics model, including the soft contacts. Simulations with multiple quadrupedal robots demonstrate that the proposed approach enables traversing soft terrains with improved stability and efficiency. Furthermore, the performance benefits of including the compliance in the MP and TC are evaluated. Finally, experiments on the SOLO12 robot walking on soft terrain validate the proposed approach’s effectiveness.

Introduction

Legged robots are designed to traverse a wide variety of natural terrains, including soft ground conditions such as snow, mud, and sand. However, the majority of existing control strategies do not account for the terrain compliance, leading to reduced efficiency and performance.

This work presents a control strategy for legged robots that considers the softness of the terrain. It adopts a two-control-blocks architecture composed of a Motion Planner (MP) and a Tracking Controller (TC). For the first time, both blocks consider the contact compliance. The MP uses the novel Soft Bilinear Inverted Pendulum (SBIP) model to compute a feasible trajectory for the robot. The TC employs considers the full robot dynamics and the soft contact model, and computes the optimal joint torques using Hierarchical Optimization (HO). The proposed approach is validated through simulations and experiments on multiple quadrupedal robots. Additionally, the proposed approach is compared with the state-of-the-art and the effects of including the compliance in the MP and/or TC are evaluated.

Block diagram of the proposed control architecture.
Block diagram of the proposed control architecture.

Results

Key Performance Indicators

The heading and lateral Root Mean Square Error (RMSE) are

hRMSE=i=1N(vh,ivh,ides)2N,lRMSE=i=1N(vl,ivl,ides)2N\begin{aligned} h_\mathrm{RMSE} &= \sqrt{\frac{\sum_{i=1}^{N}(v_{\mathrm{h}, i} - v_{\mathrm{h}, i}^\mathrm{des})^2}{N}}, \\ l_\mathrm{RMSE} &= \sqrt{\frac{\sum_{i=1}^{N}(v_{\mathrm{l}, i} - v_{\mathrm{l}, i}^\mathrm{des})^2}{N}} \end{aligned}

where vh,iv_{\mathrm{h}, i} and vh,idesv_{\mathrm{h}, i}^\mathrm{des} are respectively the measured and commanded base velocity in the heading direction at the iith instant, and similarly for the lateral direction; while NN is the total number of measurements.

The slippage along a trajectory is computed as the integral of the feet’s horizontal movements while in contact with the terrain

slip=f=14i=1Ncfvf,iΔt\mathrm{slip} = \sum_{f = 1}^{4} {\sum_{i = 1}^{N} {c_f |v_{f, i}| \Delta t}}

where cfc_f is equal to 11 if the ffth foot is in contact with the terrain, and 00 otherwise; the velocity of the ffth foot at the iith instant is vf,iv_{f, i}.

The Cost of Transport (CoT) is computed by assuming that most of the energy is lost due to thermal effects and not due to the mechanical work of the actuators. It is computed with

CoT=i=1nvhor,ivides/videsi=1nτi2\mathrm{CoT} = \frac{\sum_{i = 1}^{n} {\vec{v}_{\mathrm{hor}, i} \cdot \vec{v}_i^\mathrm{des} / |\vec{v}_i^\mathrm{des}}|} {\sum_{i = 1}^{n} {\vec{\tau}_i^2}}

where vhor,i\vec{v}_{\mathrm{hor}, i} and vides\vec{v}_i^\mathrm{des} are respectively the horizontal velocity and horizontal reference velocity at the iith instant.

Simulations

Controller Behavior

ANYmal C robot traversing a soft terrain.
SOLO12 robot traversing a soft terrain.

Performance Comparison

Key Performance Indicators comparison.
Key Performance Indicators comparison.

Fall Performance Comparison

Classic control approach.
Proposed control approach.

Experiments

Proposed approach traversing a flat soft terrain.
Proposed approach traversing an inclined soft terrain.

Solution Approach

Full Dynamics Model

The full dynamics model of a legged robot is

M(q)v˙+h(q,v)=STτ+JcT(q)fc {M}({q})\dot{{v}} + {h}({q}, {v}) = {S}^T {\tau} + {J}^T_\mathrm{c}({q}) {f}_\mathrm{c}

where q{q} is the generalized coordinates vector, v{v} is the generalized velocity vector, M(q){M}({q}) is the mass matrix, h(q,v){h}({q}, {v}) is the vector of Coriolis and centrifugal forces, S{S} is the selection matrix, τ{\tau} is the joint torques vector, Jc(q){J}_\mathrm{c}({q}) is the contact Jacobian matrix, and fc{f}_\mathrm{c} is the contact forces vector.

Soft Bilinear Inverted Pendulum

The SBIP consists in a LIP that lies on a soft surface, modeled as a linear spring-damper system in the normal direction. The dynamic equations are

x¨CoM=g+z¨CoMhCoM(xCoMxZMP)y¨CoM=g+z¨CoMhCoM(yCoMyZMP),z¨CoM=δ¨=g+1m(kpδ+kdδ˙), \begin{aligned} \ddot{x}_\mathrm{CoM} &= \frac{g + \ddot{z}_\mathrm{CoM}}{h_\mathrm{CoM}} (x_\mathrm{CoM} - x_\mathrm{ZMP}) \\ \ddot{y}_\mathrm{CoM} &= \frac{g + \ddot{z}_\mathrm{CoM}}{h_\mathrm{CoM}} (y_\mathrm{CoM} - y_\mathrm{ZMP}), \\ \ddot{z}_\mathrm{CoM} &= - \ddot{\delta} = - g + \frac{1}{m} \left( k_\mathrm{p} \delta + k_\mathrm{d} \dot{\delta} \right), \end{aligned}

where xCoMx_\mathrm{CoM}, yCoMy_\mathrm{CoM}, and zCoMz_\mathrm{CoM} are the coordinates of the Center of Mass (CoM) of the robot base, xZMPx_\mathrm{ZMP} and yZMPy_\mathrm{ZMP} are the coordinates of the ZMP, gg is the module of the gravity acceleration, mm is the total mass of the robot, and hCoMh_\mathrm{CoM} is the height of the CoM relative to the terrain. Finally, terrain deformation in the SBIP contact point is δ\delta, while kpk_\mathrm{p} and kdk_\mathrm{d} are the terrain stiffness and damping, respectively.

Soft Bilinear Inverted Pendulum model.
Soft Bilinear Inverted Pendulum model.

Motion Planner

The Motion Planner uses Model Predictive Control (MPC) to compute a feasible trajectory for the robot. It employs a simplified model (i.e. the SBIP) and optimized over a “large” time horizon.

The MPC computes the optimal ZMP positions along a sliding window. The base trajectory is derived from the ZMP positions and the SBIP model dynamics. The feet trajectories are computed using a simple heuristic that utilized the ZMP positions.

Whole-Body Controller

The Whole-Body Controller (WBC) is a Tracking Controller that computes the optimal joint torques to achieve motion tracking. It considers the full robot dynamics model over a “short” time horizon.

A legged robot mush satisfy a wide range of constraints with different importances and potentially conflicting with each other. Hierarchical Optimization solves this problem by solving a set of conflicting tasks while respecting an assigned priority order.

The set of tasks and their priorities are

PriorityTasks
1Physical consistency
2Actuation torque limits
Contact friction cone limits
Force modulation
3Contact constraints
4Base linear trajectory tracking
Base angular trajectory tracking
Swing feet trajectory tracking
5Energy minimization
Contact forces minimization

Each task is formulated as a set of linear equality and inequality constraints, as follows

{Apxbp=se,p,Cpxdpsi,p.\left\lbrace \begin{aligned} A_p x - b_p &= s_{\mathrm{e}, p}, \\ C_p x - d_p &\leq s_{\mathrm{i}, p}. \end{aligned} \right.

Here, x=[v˙TfcTδdT]Tx = \begin{bmatrix} \dot{v}^T & f_c^T & \delta_d^T \end{bmatrix}^T is the optimization vector, where v˙\dot{v} is the generalized velocity vector, fcf_c are the contact forces, and δd\delta_d are the desired terrain deformations. Conversely, se,ps_{\mathrm{e}, p} and si,ps_{\mathrm{i}, p} are the equality and inequality slack variables, respectively.

Conclusion

This paper presented a novel approach for quadrupedal locomotion in the presence of soft contacts. The proposed control architecture consists of two blocks: the Motion Planner (MP) and the Tracking Controller (TC). The benefits of including the compliance in the MP and TC were evaluated through simulations and experiments on multiple quadrupedal robots.

BibTeX citation

    @article{DeBenedittis2025Soft,
  author = {De Benedittis, Davide and Angelini, Franco and Garabini, Manolo},
  journal = {IEEE Transactions on Systems, Man, and Cybernetics: Systems}, 
  title = {Soft Bilinear Inverted Pendulum: A Model to Enable Locomotion With Soft Contacts}, 
  year = {2025},
  volume = {55},
  number = {2},
  pages = {1478-1491},
  keywords = {Legged locomotion;Quadrupedal robots;Foot;Vectors;Optimization;Computational modeling;Trajectory;Tracking;Planning;Jacobian matrices;Contacts;legged locomotion;optimal control;predictive control;quadratic programming},
  doi = {10.1109/TSMC.2024.3504342}
}