High-Frequency Model Predictive Control for Jumping Gait in Parallel Quadruped Robots

In recent years, the development of legged robots has garnered significant attention due to their ability to traverse complex terrains with agility and efficiency. Among these, the quadruped robot, often referred to as a robot dog, represents a prominent category capable of executing various gaits such as walking, trotting, and jumping. The jumping gait, in particular, poses unique challenges due to its dynamic nature, characterized by brief ground contact times and high instantaneous forces, leading to underactuated states of the robot’s body. Addressing these challenges requires advanced control strategies that can handle rapid changes and uncertainties. In this context, model predictive control (MPC) emerges as a powerful tool, leveraging system models to predict and optimize future behaviors, thereby enhancing stability and performance. This article explores the application of high-frequency MPC for controlling the jumping gait of a parallel quadruped robot, focusing on model simplification, force distribution, and experimental validation to achieve efficient and stable locomotion.

The core of our approach lies in simplifying the complex dynamics of the quadruped robot into a more manageable equivalent model. For the jumping gait, we reduce the quadruped robot to a planar bipedal model, which captures the essential dynamics while minimizing computational complexity. This simplification is justified when the leg mass is less than 10% of the total robot mass, as it allows for faster MPC updates, crucial for real-time control. The planar bipedal model assumes symmetry and independent dynamics in the horizontal and vertical directions, enabling separate control strategies for each axis. The state of the robot is defined in a generalized coordinate system, with the center of mass coordinates in the horizontal and vertical directions, and the pitch angle representing orientation. The dynamic equations governing this system are derived from rigid body dynamics, where the forces exerted by the legs on the ground are critical for motion control.

To formalize the dynamics, we define the state vector as \( X = [x, \dot{x}, y, \dot{y}, \theta, \dot{\theta}, -g] \), where \( x \) and \( y \) represent the horizontal and vertical positions of the center of mass, \( \dot{x} \) and \( \dot{y} \) their derivatives, \( \theta \) the pitch angle, \( \dot{\theta} \) its derivative, and \( -g \) the gravitational acceleration incorporated for convenience. The control input vector is \( U = [F^x_f, F^y_f, F^x_h, F^y_h] \), denoting the horizontal and vertical forces applied by the front and hind legs. The state equation is expressed as \( \dot{X} = A X + B U \), where \( A \) and \( B \) are matrices derived from the system dynamics. For instance, the acceleration terms are given by:

$$ \ddot{x} = \frac{F^x_f + F^x_h}{m} $$

$$ \ddot{y} = \frac{F^y_f + F^y_h}{m} – g $$

$$ \ddot{\theta} = \frac{F^x_f r_{yf} + F^x_h r_{yh} + F^y_f r_{xf} – F^y_h r_{xh}}{I} $$

Here, \( m \) is the robot’s mass, \( I \) the moment of inertia, and \( (r_{xf}, r_{yf}) \), \( (r_{xh}, r_{yh}) \) represent the horizontal and vertical distances from the front and hind legs to the center of mass, respectively. By discretizing this continuous-time model using the forward Euler method with a control period \( T \), we obtain a discrete state equation \( X(k+1) = \bar{A} X(k) + \bar{B}(k) U(k) \), where \( \bar{A} = E + T A \) and \( \bar{B} = T B(k) \), with \( E \) as the identity matrix. This discrete form facilitates the implementation of MPC by enabling predictions over a finite horizon.

The kinematic model of the robot dog’s legs is essential for converting between joint angles and foot positions. Each leg of the quadruped robot is modeled as a two-link mechanism, with angles \( \alpha_1 \) and \( \alpha_2 \) representing the rotations of the motors in the body frame, and lengths \( L_1 \) and \( L_2 \) for the thigh and shank, respectively. The forward kinematics allow us to compute the foot position \( (x_b, y_b) \) in the body frame from the motor angles using trigonometric relations. The virtual leg angle \( \beta \) and length \( L_3 \) are derived as:

$$ L_3 = \sqrt{L_1^2 \cos^2\left(\frac{\alpha_1 – \alpha_2}{2}\right) + L_2^2 – L_1^2 \sin^2\left(\frac{\alpha_1 – \alpha_2}{2}\right)} $$

$$ \beta = \frac{\alpha_1 + \alpha_2}{2} $$

Then, the coordinates are given by \( x_b = L_3 \cos \beta \) and \( y_b = -L_3 \sin \beta \). Inverse kinematics enable the computation of motor angles from desired foot positions, which is crucial for trajectory planning. For example, given \( (x_b, y_b) \), we compute \( L_3 = \sqrt{x_b^2 + y_b^2} \) and \( \beta = -\frac{\pi}{2} – \arctan\left(\frac{-y_b}{x_b}\right) \), leading to:

$$ \alpha_1 = \frac{\pi}{2} – \beta + \arccos\left(\frac{L_3^2 + L_1^2 – L_2^2}{2 L_1 L_3}\right) $$

$$ \alpha_2 = \frac{\pi}{2} – \beta – \arccos\left(\frac{L_3^2 + L_1^2 – L_2^2}{2 L_1 L_3}\right) $$

The Jacobian matrix, derived by partial differentiation of the foot positions with respect to the motor angles, maps forces in the body frame to motor torques. If \( F^x_b \) and \( F^y_b \) represent the forces in the body frame, the motor torques \( \tau_1 \) and \( \tau_2 \) are computed as:

$$ \begin{bmatrix} \tau_1 \\ \tau_2 \end{bmatrix} = \begin{bmatrix} \frac{\partial x_b}{\partial \alpha_1} & \frac{\partial y_b}{\partial \alpha_1} \\ \frac{\partial x_b}{\partial \alpha_2} & \frac{\partial y_b}{\partial \alpha_2} \end{bmatrix} \begin{bmatrix} F^x_b \\ F^y_b \end{bmatrix} $$

Transformation between world and body frames is achieved using the rotation matrix based on the pitch angle \( \theta \), allowing forces to be applied correctly during motion.

Model predictive control forms the backbone of our strategy for managing the jumping gait of the quadruped robot. The MPC framework involves predicting future states over a horizon and optimizing control inputs to minimize a cost function while adhering to constraints. The discrete state equation is used to form the prediction model, where the output over a prediction horizon \( n \) is expressed as \( \bar{X}(k) = \psi(k) X(k) + \lambda(k) \bar{U}(k) \), with \( \bar{X}(k) \) representing the predicted states and \( \bar{U}(k) \) the control sequence. The cost function \( f(k) = (\bar{X}(k) – \bar{X}_{\text{ref}}(k))^T Q (\bar{X}(k) – \bar{X}_{\text{ref}}(k)) + \bar{U}^T(k) R \bar{U}(k) \) is minimized, where \( Q \) and \( R \) are weight matrices for states and controls, respectively, and \( \bar{X}_{\text{ref}}(k) \) is the reference trajectory. This is transformed into a quadratic programming problem:

$$ f(k) = \frac{1}{2} \bar{U}^T(k) H \bar{U}(k) + \bar{U}(k) f(k) $$

with \( H = 2(\lambda^T(k) Q \lambda(k) + R) \) and \( f(k) = 2\lambda^T(k) Q (\psi(k) X(k) – \bar{X}_{\text{ref}}(k)) \). The solution yields the optimal control sequence, with the first element applied to the system at each step, enabling real-time feedback.

Practical constraints are integral to the MPC implementation. For the quadruped robot, leg forces must satisfy friction and motor torque limits. The vertical force \( F^y \) is bounded by \( F_{\min} \leq F^y \leq F_{\max} \), and the horizontal force \( F^x \) by \( -\mu F^y \leq F^x \leq \mu F^y \), where \( \mu \) is the friction coefficient. These constraints ensure that the generated forces are physically feasible, preventing slippage or excessive motor demands. After computing the aggregate forces for the front and hind legs using MPC, we distribute them to individual legs of the robot dog using a proportional-derivative (PD) controller. This accounts for deviations in yaw and roll angles, enhancing stability. The adjustments \( dF_{\text{yaw}} \) and \( dF_{\text{roll}} \) are computed as:

$$ dF_{\text{yaw}} = k_{p,\text{yaw}} (Y_{\text{ref}} – Y_d) + k_{d,\text{yaw}} (\dot{Y}_{\text{ref}} – \dot{Y}_d) $$

$$ dF_{\text{roll}} = k_{p,\text{roll}} (R_{\text{ref}} – R_d) + k_{d,\text{roll}} (\dot{R}_{\text{ref}} – \dot{R}_d) $$

where \( k_p \) and \( k_d \) are gains, and the subscripts denote reference and actual values. The forces for each leg—front right (FR), front left (FL), hind right (HR), and hind left (HL)—are then allocated as:

$$ F^x_{fr} = \frac{F^x_f}{2} + dF_{\text{yaw}}, \quad F^x_{fl} = \frac{F^x_f}{2} – dF_{\text{yaw}} $$

$$ F^x_{hr} = \frac{F^x_h}{2} + dF_{\text{yaw}}, \quad F^x_{hl} = \frac{F^x_h}{2} – dF_{\text{yaw}} $$

and similarly for vertical forces with \( dF_{\text{roll}} \). This distribution ensures that the quadruped robot maintains balance and tracks desired orientations during dynamic movements.

During the swing phase, when legs are not in contact with the ground, trajectory control becomes crucial for repositioning the feet for the next stance. We use Bézier curves to generate smooth swing trajectories, defined by an 11th-order polynomial:

$$ B(t) = \sum_{i=0}^{n} \binom{n}{i} P_i (1 – t)^{n-i} t^i, \quad t \in [0,1] $$

where \( P_i \) are control points, \( n = 11 \), and \( t \) is normalized time over the swing period \( T_s \). The endpoint in the horizontal direction is set based on the reference velocity \( v_{\text{ref}} \) and actual velocity \( v_d \), with a gain \( k_v \):

$$ P_{x,11} = \frac{T_l}{2} v_{\text{ref}} + k_v (v_{\text{ref}} – v_d) $$

where \( T_l \) is the stance period. This planning ensures that the foot lands at an appropriate position to absorb impact and facilitate continuous motion. Additionally, virtual forces during the swing phase, derived from motor feedback torques, help detect ground contact. If the computed foot force exceeds a threshold based on aerial references, it indicates touchdown, allowing for seamless phase transitions.

To validate our control strategy, we conducted experiments on a custom-built parallel quadruped robot. The robot dog features four legs with parallel structures, each driven by motors capable of high torque output. Key parameters of the experimental setup are summarized in the table below:

Parameter Value
Dimensions 430 mm × 280 mm × 60 mm
Thigh Length 92 mm
Shank Length 220 mm
Total Mass 13 kg
Motor Type TMotor AK80-6
Max Motor Torque 12 N·m
Encoder Type MA702
IMU Type Yesense YIS100
IMU Roll/Pitch Accuracy 0.3°
IMU Yaw Accuracy 0.5°
IMU Data Rate 195 Hz
Supply Voltage 24 V

The experimental setup involved comparing high-frequency MPC (update rate near 500 Hz) with low-frequency MPC (update rate near 100 Hz) to assess control effectiveness. The robot was tasked with accelerating from rest to set velocities and maintaining them, with performance evaluated based on velocity and position tracking. The high-frequency MPC demonstrated superior tracking, with velocity errors below 0.2 m/s and position errors around 0.1 m at a set speed of 1.5 m/s. In contrast, low-frequency MPC resulted in larger errors, up to 0.46 m/s in velocity and 0.23 m in position, along with significant oscillations. The periodic forces under high-frequency MPC were smoother, with horizontal forces peaking at approximately 14 N and vertical forces at 90 N, whereas low-frequency MPC showed erratic force profiles with higher peaks and instabilities.

Further tests on slopes of 4° and 8° confirmed the adaptability of our approach. Although speed variations occurred due to terrain inclination, the quadruped robot maintained stable operation, with the high-frequency MPC effectively compensating for disturbances. The results highlight that simplified models enable faster computation, making high-frequency updates feasible for real-time control of dynamic gaits like jumping.

In conclusion, our research presents a high-frequency model predictive control framework tailored for the jumping gait of parallel quadruped robots. By simplifying the robot dog model to a planar bipedal system, we reduce computational complexity, allowing MPC updates at 500 Hz. The integration of kinematics and dynamics models, along with PD-based force distribution, ensures precise control during both stance and swing phases. Experimental validation on a custom robot dog demonstrates enhanced tracking performance and force smoothness compared to lower-frequency alternatives. This work underscores the potential of high-frequency MPC in improving the efficiency and stability of quadruped robots across diverse terrains, paving the way for more agile and reliable robotic systems in practical applications.

Scroll to Top