Abstract
This article presents the modeling process of the lower part of a humanoid biped robot in terms of kinematic/dynamic states and the creation of a full dynamic simulation environment for a walking robot using MATLAB/Simulink. This article presents two different approaches for offline walking pattern generation: one relying on a closed-form solution of the linear inverted pendulum model (LIPM) mathematical model and another that considers numerical optimization as means of desired output trajectory following for a cart table state-space model. This article then investigates the possibility of introducing solution-dependent modifications to both approaches that could increase the reliability of basic walking pattern generation models in terms of smooth single support–double support phase transitioning and power consumption optimization. The algorithms were coded into offline walking pattern generators for NAO humanoid robot as a valid example and the two approaches were compared against each other in terms of stability, power consumption, and computational effort as well as against their basic unmodified counterparts.
Keywords
Introduction
A humanoid robot is a robot that resembles human body form and is bipedal in nature. The first human-resembling robot was developed by Ichiro Kato et al. from Waseda University in 1973. That robot was able to communicate and interact with the environment through some sensors and receptors. It could achieve a stable dynamic gait and manipulate some objects. Waseda University has been one of the leading research institutes for anthropomorphic robots. Ten years following that discovery, Waseda University has produced a handful of humanoid robots like the musician robot WABOT-2 made in 1984, Hadaly-2, which cooperates with a human partner to do specific jobs, 1 and the biped robot, WABIAN, which could perform impressive walking maneuvers in 1997. 2 Based on the promising fruits of research in that field, Waseda University established the Humanoid Robotics Institute in April 2000 to fund research endeavors, which aim to construct an industrial environment in which humans and robots could cooperate with humans lying in the top tier decision-making hierarchy and robots in a lower tier in an advanced internet of things (IOT) structured industrial facility. 3 –5
Surprisingly, it is expected that a robot would perform domestic tasks such as house cleaning and organizing for middle-aged and old individuals all within few years. 6 The humanoid will be able to integrate sensory data and perform intelligent actions, which include communication with individuals using paradigms such as natural language processing (NLP), facial expression analysis, and high-level motion control. 7,8 Evidently, it is essential that humanoid robot research go hand in hand with other related research areas such as biology, human psychology, and social studies. 9,10
Later, various studies that focused on bipedal robots, 11 –13 control strategies, and stable dynamic walking 14,15 have been conducted. These studies handled every aspect of human dynamic activities such as dynamic walking, push recovery from an unknown external force, adapting to uneven terrains, and so on. Boston Dynamics is known worldwide for its contribution to these fields through a collection of state-of-the-art biped and quadruped robots, including robots like BigDog, Spot, Handle, and Atlas. 16,17
Furthermore, intelligent behavior and autonomy were added to humanoid robots and several studies have been conducted on the topic. Perhaps, the most notable bipedal robot was Asimo developed by Honda, which could perform tasks like walking, running, and even more advanced tasks like playing football. 18 Several algorithms that basically lie in the domains of environment perception, robot localization, and environment mapping have been explored to develop some autonomous behaviors for humanoid robots. 19,20 Also, probabilistic approaches helped the robot to construct maps for different environments and localize itself in the environment using simultaneous localization and mapping algorithms and sensor fusion paradigms like extended kalman filter (EKF) and particle filter-based approaches. 21 One of the most challenging aspects of humanoid robot design is the technique used in walking pattern generation since a biped robot is an inherently unstable structure in essence. 22 Toward that end, several models have been adopted like the famous LIPM model, which simplifies the robot into a single point mass lying at the end of an inverted pendulum. 23 –26 Some adaptations have been added to the concept like the double inverted pendulum model in which the lower and upper parts are treated like two connected inverted pendulums 27,28 and the flywheel addition that further complicates the model by considering rotational inertia for the pendulum end-point rather than just mass. A more versatile model for gait generation and perhaps the most widely used is the cart table model that basically simplifies the robot as a cart moving back and forth on a table at a constant height from the ground and introduces the zero moment point (ZMP) concept. 29 –32 This article proposes novel solutions to both basic models, which could help enhance the walking pattern generation process and make the basic models more flexible and considerate of practical walking considerations like smooth single support-double support transitioning and overall power consumption. This article evaluates the performance metrics of the presented closed form and numerical approaches for walking pattern generation and takes the NAO humanoid robot as a valid example. The results were validated using MATLAB/Simulink simulations.
Robot modeling
Study of NAO kinematic structure
NAO is an autonomous bipedal robot made by Aldebaran robotics. The version under study here is version 4 with 25 degrees of freedom overall. In the work presented here, the main focus is on the robot’s lower part, which includes the legs, pelvis, and has 11 degrees of freedom. Each leg has two degrees of freedom at the ankle, one degree of freedom at the knee, and two degrees of freedom at the hip. The pelvis is equipped with two coupled joints each attached to one of the two robot hips. The rotation axes of the two coupled joints are inclined to the outside at 45°. Normally, in most classical humanoid robot mechanical designs, the pelvis is composed of three separate joints each having a specific degree of freedom. The NAO design defies this convention by introducing coupled joints in the pelvis design, and despite the gains summarized in fewer motors, less power consumption, and optimized space, this design introduces complexities in the kinematic solution as the coupling prevents the upper part from rotating around the yaw axis when both legs are in support, which demands some form of kinematic decoupling to allow for a proper kinematic solution. An illustration for the NAO lower part kinematic structure is shown in Figure 1.

NAO kinematic structure.
Forward kinematics is derived based on a chain rule of homogeneous transformations, which is later interpreted as a series of closed-form equations. First, it is crucial to assign both a global (world frame) and a robot local frame and then obtain the necessary transformations to create the closed-form solution.
The translation and orientation of joint j with respect to adjacent joint i in the 3D space
33
is described using a 4 × 4 transformation matrix
where
A point
Applying these formulas altogether with Denavit–Hartenberg method yields the following kinematic equations
where X, Y, and Z represent the pelvis link center coordinates in global x, y, and z axes, respectively, while Fx , Fy , and Fz represent the global coordinates of the reference point on the foot sole.
As for inverse kinematics, a closed-form solution is considered to be the optimal solution since it requires minimal computational effort. Based on this fact, a geometrical solution of inverse kinematics was developed using trigonometric relations. The inverse kinematics closed-form solution can be used to generate the trajectories of the joint angles and help track the desired center of mass trajectory.
Locating the center of mass location relative to the global frame is a crucial step in the walking pattern generation algorithm especially in the joint angle trajectory correction step because this step helps track the exact center of mass trajectory and make it follow the desired center of mass (COM) motion profile for a stable gait. First, it is required to locate the center of mass of each link relative to the global frame, then knowing all links’ center of mass coordinates and mass properties; it is possible to locate the robot COM coordinates as a whole. In the analysis presented here, it is assumed that the upper part of the robot is a rigid body whose center of mass is determined according to the current pose of the upper part, which has to do with the manipulation task the robot is performing like raising hands, objects, head turning, and so on. The COM transforms are computed as follows
where Ti represents the i’th link center of mass frame transformation matrix.
Link center of mass can be obtained by the following relation
where Ci is the i’th link center of mass global coordinates and is the foot sole reference point coordinates relative to the global frame. The robot center of mass is obtained by the following equation
where mi is the mass of the i’th link. The kinematic model was constructed on MATLAB/Simulink and validated by inserting a desired trajectory and validating the output trajectory by comparing it to the input/desired trajectory. The COM tracking algorithm showed convergence with a reasonable root mean square error (RMSE) that reached 0.000382 m for x coordinates, 0.000484 m for y coordinates, and 0.000148 m for z coordinates (Figure 2).

COM trajectory versus time (a) x-coordinate, (b) y-coordinate, and (c) z-coordinate.
Dynamic model
A contact model was developed for ZMP measurement based on placing four force sensors (FSRs) at each foot sole to measure the resultant vertical force and calculate the corresponding ZMP location using SimMechanics’ ground contact library. To confirm the validity of the suggested contact model, simulations were carried out to test both the friction and FSR models. The FSR model steady-state response was tested by statically placing an object of known weight on the ground and recording the average reading of an FSR. The offset of the reading for a 50 kg object was found to be 7.95 N and the variance of the reading was found to be 0.4023 N2, as shown in Figure 3(a), and for a 10 kg object, the offset of the reading was found to be 2.1 N and the variance was found to be 0.4011 N2, as shown in Figure 3(b).

Normal force measurement versus time for an FSR (a) 50 kg object and (b) 10 kg object.
It is important to test the frequency response of an FSR since the walking cycle is repetitive and the impact forces on the FSR will follow a periodic pattern. A vertical sinusoidal force was made to act on the object to view the results in terms of attenuation and phase delay. A 10-Hz force of amplitude 5 N had a gain of 0 dB and a phase delay of 0 rad, as shown in Figure 4(a), while a 500-Hz force of amplitude 5 N had a gain of 0 dB and a phase delay of 0 rad, as shown in Figure 4(b). Finally, A 10-kHz force of amplitude 5 N had a gain of −1.93 dB and a phase delay of 0.63 rad, as shown in Figure 4(c).

Normal force measurement versus time for an FSR: (a) 10 Hz, (b) 500 Hz, and (c) 10 kHz. FSR: force sensor.
The friction model was tested by moving a 1 kg object horizontally on the ground through a linearly varying horizontal force with slope 1 N/s, varying the static/dynamic coefficients of friction values and measuring the resultant resistance force, as shown in Figure 5(a), in which the static coefficient of friction was declared to be 0.7 and dynamic coefficient of friction to be 0.6 and Figure 5(b) in which the static coefficient of friction was declared to be 0.9 and dynamic coefficient of friction to be 0.8.

Friction force versus time for an FSR: (a) first case and (b) second case. FSR: force sensor.
Walking pattern generation
Analytical approach
The 3D LIPM dynamics (Figure 6) is first analyzed to formulate the basic walking pattern generation algorithm followed by introducing modifications.

3D extension of the LIPM.
By resolving the components of the “push” force, the following equations are obtained
The motion equations of the COM are given by Newton’s second law as follows
By realizing that motion in the vertical direction is constrained to a plane parallel to the x-y plane and lies at a constant distance zc from it, the following is deduced
By taking Laplace and inverse Laplace transforms for equation (30), the following time domain solution is obtained
The same solution can be derived for y-coordinate differential equation (31). In this context, a “walking primitive” needs to be explored. A walking primitive represents the unit upon which the entire walking pattern is based. After a support time Ts
is assumed, a walking primitive can be imagined, as shown in Figure 7, as a 3D LIPM, whose base is fixed to the foot placement point (physically, a predetermined point on the foot sole selected by the gait designer). It can easily be shown that a desired walk primitive could be fully described by its terminal states (

Illustration for a walking primitive.
Using the analytical solution developed for an inverted pendulum earlier and by observing the symmetric nature of the desired walk primitive, the following equation can be deduced
Equation (34) can be replicated easily for y-axis. To achieve the desired criteria of the walk primitive mentioned earlier, the initial values can be eliminated from equation (34) and its y-replica and replaced with their mathematical desired equivalents as follows
By reorganizing the equations, the following final expression for desired final velocities is obtained
Several walking primitives are connected back to back by reversing the sign of the y-component after each support exchange to account for the exchange between right and left feet. It is crucial to determine the relationship between the robot’s foot placements at each instant of time in terms of x and y spacing as follows
Equation (38) simply indicates how the sequence of N footsteps can be represented mathematically, having the x-coordinate of the n’th footstep equal to the summation of the x-coordinate of the last footstep and the step length sx taken by the robot. The same can be deduced for the n’th y-coordinate with the only difference being the step sign flipping at each instant to represent the support exchange between the right and left legs, respectively
Equation (39) shows that the desired final displacement of the center of mass trajectory along local x-axis is equal to half the magnitude of the step plus the x-coordinate of the foot placement point. It also shows a similar expression for the desired final displacement of COM trajectory along local y-axis with the exception of the sign, which flips at each instant of time to reflect support exchange. The equations derived for the LIPM show that the desired situation is not guaranteed to happen and the best hope would be to try to optimize the trajectory to follow the desired behavior as much as possible. The only variable that could be used to minimize the error between the desired and actual final conditions is the foot placement location. By modifying the foot placement position and considering it as an optimization variable, a better solution can be obtained that could achieve the requirements of a consistent gait. An objective function can be formulated as follows
The optimal foot placement can be computed by obtaining the partial derivative of the objective function A with respect to the foot placement Double support phase is ignored and support exchange is jerky The proposed algorithm does not consider the locomotion cost of transport, the biped robot has a limited capacity battery, and therefore, energy consumption optimization is an important factor that is ignored in the formulation
The model assumes an ideal condition in which support exchange occurs instantly, which is an impossible situation physically speaking. In a real-world situation, even with joint angle trajectory smoothening, such instantaneous exchange would cause the robot to highly decelerate at instants of support exchange and most likely fall. This problem can be solved by introducing a double support region in the COM trajectory with a predetermined double support period between each two walk primitives. Analyzing this would lead to the conclusion that a COM profile has to be inserted into the gap between two walk primitives whose initial conditions are the final position and final velocity of the walk primitive number (n−1) and whose terminal conditions are the initial position and velocity of the walk primitive number (n), which means we could have four equations. This suggests using a fourth order polynomial having four constant coefficients. By solving four equations in four unknowns, these coefficients can easily be determined. The addition of the double support phase profile in between the original walk primitives would increase the gait time since the total gait time will be divided between single support and double support phases. To obtain a natural gait, the double support phase period should not be higher than 0.1 times of the single support phase period
By taking the derivative of the polynomial, the velocity profile can also be obtained. The second limitation to the LIPM approach is ignoring the robot’s power consumption. The target in the standard LIPM model is to make the base of the pendulum (also known as the ZMP) centered at a specific point on the foot sole. In truth, this is not the case for human natural walking. 34 The natural ZMP trajectory is not so stiff and the foot placement point on the foot sole does not have to stick to one place during the walk primitive as long as it remains within the area of the support polygon. Therefore, a reasonable approach toward reducing the torques exerted by the robot motors (and hence power consumption) would suggest relaxing the constraints on the foot placement point. The foot placement point represents the point through which the kick force acts on the COM (pendulum end). Therefore, manipulating the position of the foot placement would also mean shifting the point of intersection of the kick force with the horizontal ground plane. One way to achieve this without modifying the pendulum concept is shifting the base of the pendulum beneath the ground, as shown in Figure 8, which represents the pendulum base shifted beneath the ground by Zp , while maintaining kick force line of action within ground support polygon (i.e. kick force intersection point with the ground plane changes location within the support polygon).

Pendulum base shift.
Due to the base shift, the mathematical model of the inverted pendulum will be slightly modified as follows
Taking Laplace/inverse Laplace transforms yields as follows
The value of Zp must be restrained to obtain a reasonable trade-off between stability and energy optimization. To do this, a suitable area contained within the support polygon is to be chosen and has to have its boundaries slightly far away from the support polygon boundaries to create a safety margin because if the ZMP approaches the support polygon boundaries the robot will be marginally stable. The chosen area is called the “safe zone,” as shown in Figure 9.

ZMP safe zone.
After selecting the x and y boundaries of the safe zone relative to the local frame of the walk primitive, a suitable Zp value can be obtained by triangle symmetry as follows
The same equation can be used for y-axis in the same manner. The upgraded LIPM algorithm can be formulated, as shown in Algorithm 1.
LIPM_WPG (
Numerical approach
Another way of interpreting the biped robot dynamics is by representing it in terms of a simpler model known as the cart table model. In this model, a cart with mass runs back and forth on top of a massless table. The table can keep its balance by pushing the cart forward and backward. The cart responds by an equal and opposite force causing the table to maintain balance by a positive counter-moment that overcomes the negative moment caused by the cart weight. The mass represents the robot’s mass and its location defines the location of the robot COM. The kinematic states of the table also represent the kinematics states of the COM (Figure 10).

Cart table model.
The cart table model case resembles that of a point mass located at a specific height from the ground, the table tries to balance itself by applying a force on the cart as follows
The cart responds by an equivalent force in the opposite direction, thus creating a moment about the table ZMP as follows
Also, the weight of the cart creates a moment about the ZMP as follows
The ZMP is the point at which all moments vanish, therefore
By eliminating common factors and rearranging equation variables, the ZMP location can be calculated as follows
A very valuable advantage of the cart table model is that it does not need to cut down the walking pattern into a series of walking primitives and even does not need to treat single support and double support phases as separate cases. The walking pattern flow can be continuous without breakdowns. The cart table model in its pure mathematical form is not useful and needs to be treated in a different way. To do this, the principles of modern control theory are used to create a state-space model instead of solving the model using classical methods
It can be easily shown that the above state-space system is controllable and observable by evaluating the controllability and observability matrices. A servo control system is inefficient in terms of time response. This initiates the need for a dynamic programming approach to optimize a linear system under definite constraints. Model predictive control (MPC) is chosen since MPC can adapt to sudden future set-point changes, which happen to be the case during the support feet exchange. A loop in which a set of arbitrary control actions are fed to the cart table model and the output ZMP trajectory is compared to desired ZMP trajectory continues until the error (in the form of an objective function) is minimized globally. Only then, the resultant set of control actions is then deemed optimal (Figure 11).

Model predictive control approach.
First, the relationship between the present and future values of the states of the system is to be determined by discretizing the state-space model
The second step is to formulate the optimization problem’s objective function. The optimization problem’s goal would be minimizing the deviation of the actual ZMP trajectory from the desired ZMP trajectory as well as minimizing the overall input jerk to the system
where Q and R are the performance and effort weight matrices, respectively, and N is the prediction horizon. The last step is to determine the optimization problem constraints. The only constraints on the system are state constraints and input jerk constraints. The states have no specific constraints except the margins of the walking area (room or building) and since the robot workspace is naturally considered very small relative to room space, these constraints can be ignored and left for the gait designer to evade. Also, the input jerk to the system has an upper bound in terms of magnitude. This constraint can be easily described as follows
The solution strategy would be to use an optimization toolbox to minimize the objective function J by producing an optimal series of control actions (jerks) that would make the system output (ZMP trajectory) follow the desired pattern. The linear optimization parametric problem was formulated symbolically on MATLAB and CasADi library for linear/nonlinear optimization was used for solving the objective function problem under maximum allowable jerk constraint (Algorithm 2).
Unlike the first approach, the numerical approach is flexible when it comes to double support phase insertion, which can be done by inserting smooth ZMP reference trajectory transitions with finite slopes, as shown in Figure 12.

ZMP reference trajectory: (a) without double support and (b) with double support.
The criterion that is worth considering is power consumption optimization. The best way to investigate the optimal strategy for this in the present numerical approach is by observing the human gait pattern, such gait is the product of thousands of years of evolutionary natural selection. A study made by the Department of Neurorehabilitation Sciences, Istituto Auxologico Italiano, 35 suggests that the COM of the human body follows an almost sinusoidal curve during walking (Figure 13). Indeed, a human body tends to stretch the knee in the middle of the walk and then flex the knees back by the end of the walking cycle. It is therefore necessary to investigate the effect of such motion on the energy consumption and stability. This means that the COM height constraint that was presented in the standard formulation has to be canceled and instead COM height is to be defined as a function of time.

COM path in the sagittal plane.
CTM_WPG1 (
Based on the above, the mathematical model of the cart table can be modified by including a second lift force in the Z-direction
The moment due to the reaction of the cart to the lift force becomes
Therefore, the summation of moments acting about the ZMP becomes
By eliminating common factors and rearranging the equation
The state-space representation of the updated model can now be formulated as follows
To satisfy the energy optimization criteria, the work done by the push forces is to be minimized. This can be done by introducing an effort weight matrix that may have many forms. Here, the overall work done is to be minimized by minimizing the input jerk to the system. The performance weight is assigned to the minimization of the ZMP error as in the previous standard cart-table walking algorithm. Therefore, the objective function can be reformulated as follows
New constraints need to be added to the algorithm, these will include restrictions on the allowable COM height range based on robot reach, also restrictions on the maximum allowable jerk in z-direction. Total system constraints can be introduced as follows
The numerical walking pattern generator is upgraded by considering these findings (Algorithm 3). The walking pattern generation algorithm is used as part of a fully developed walking engine, where the obtained COM trajectory required to keep the robot dynamically stable during walking is fed to the inverse kinematics module and verified by the COM tracking forward kinematics module. An iterative optimization technique in which the engine moves back and forth between inverse and forward kinematics is used to reduce the error between desired and actual COM trajectory below a certain threshold till the threshold is no longer violated. The optimized angular trajectory is then fed to the robot motors after second-order filtration.
CTM_WPG2 (
Results
To validate the efficiency of the proposed algorithms against their standard counterparts and to compare the two approaches suggested in this article against each other in terms of stability, power consumption, and computational effort. A simulation scenario for NAO walking straight forward on an even terrain was conducted using SimMechanics. The walking pattern used is shown in Figure 14, which displays the footprints of the robot’s support foot during walking. Simulation parameters are given in Table 1.

First walking scenario steps.
Multibody simulation parameters.
The closed-form algorithms were used to generate the walking pattern. The RMSE for x-coordinate ZMP reached 0.0648 m for the standard closed-form approach and 0.0388 m for the upgraded closed-form approach, as shown in Figure 15(a), while RMSE for y-coordinate ZMP reached 0.0321 m for the standard closed-form approach and 0.0253 m for the upgraded approach, as shown in Figure 15(b) (

(a, b) Closed form approach ZMP variation.
The joint torques of both the standard and upgraded closed-form approaches were evaluated and compared, as shown in Figure 16. Torque RMS and peak for each joint are given in Table 2.
Closed-form joint torques.

(a–e) Joint torques for closed-form approach walking scenario.
The results show, contrary to expectations, that the ZMP following accuracy increased in the upgraded approach because relaxing the ZMP constraints reduced ZMP spikes. Also, the upgraded approach did not contribute much to power consumption optimization since only the first joint RMS and peak torques decreased while all the other joint RMS and peak torques increased slightly. This shows that ZMP relaxation did not necessarily reduce the power consumption in the actual multibody model but rather reduced the effort of some joint motors at the expense of increasing the effort of other joint motors, all while increasing the accuracy of ZMP following and hence enhancing robot stability. The generated COM trajectories of the robot using both approaches are shown in Figure 17.

(a–c) COM trajectories for closed-form approach walking scenario.
Next, the numerical generation algorithms were used to generate the same walking pattern separately. The RMSE for x-coordinate ZMP reached 0.0635 m for the standard numerical approach and 0.0164 m for the upgraded numerical approach, as shown in Figure 18(a), while the RMSE for y-coordinate ZMP reached 0.0279 m for the standard numerical approach and 0.0233 m for the upgraded numerical approach, as shown in Figure 18(b). The cart table model parameters are given in Table 3.

(a, b) Numerical approach ZMP variation.
Cart table model parameters.
These results show that the upgraded numerical approach is relatively superior in terms of ZMP following accuracy and that the upgrades have no stability compromise side effect; on the contrary, the ZMP following was improved.
The joint torques of both the standard and upgraded numerical approaches were evaluated and compared, as shown in Figure 19. The torque RMS and peak for each joint are given in Table 4.
Numerical approach joint torques

Joint torques for numerical approach walking scenario.
Observations show that the upgraded numerical approach is far more superior to the standard one in terms of power consumption optimization since the torque RMS values recorded are a strong indicator of RMS current draw and hence electrical power. The torque RMS value was reduced by almost 15% for the first joint, 18.7% for the second, 23% for the third, 34.4% for the fourth, and 60.39% for the fifth. Also, the peak torques were reduced, which suggests that the upgraded approach would help optimize motor sizing process for bipedal humanoids in general. The generated COM trajectories of the robot using both approaches are shown in Figure 20. The upgraded approach allows more freedom of motion in the vertical direction as assumed. Also, the vertical motion of the COM in the upgraded approach resembles a sinusoid as modern clinical research predicted, which provides further assurance regarding the validity of the assumptions presented earlier.

COM trajectories for numerical approach walking scenario.
Finally, the closed-form and numerical upgraded approaches are compared against each other. The simulations show that the upgraded numerical approach is superior to the upgraded closed-form approach in terms of ZMP trajectory following since it has lower RMSE in both axes. Also, the upgraded numerical approach is superior to both the standard and upgraded closed-form approaches in terms of power consumption optimization since it managed to achieve less torque values for joints 1, 2, 3, 5 and almost equal torque values for joint 4, proving, overall, that it can offer better power optimization and stabilization capabilities than a closed-form solution. The only drawback for the upgraded numerical solution is its computational expense. The computational time for the upgraded numerical approach reached 77.388005 s, while the computational time for the upgraded closed-form approach reached 6.723688 s (both approaches were tested using the same computer and same MATLAB software version).
Conclusion
Solution-dependent modifications were introduced for the basic walking pattern generation model to enhance their performance. The results for different comparisons made between closed form and numerical algorithms as well as their suggested modifications were displayed. The numerical approach shows general dominance in terms of stability and ease of formulation as well as energy consumption optimization. Introducing biologically verified modifications to the algorithm formulation related to COM height manipulation during walking drastically improved the performance and effort minimization. The closed-form solution used a ZMP relaxation strategy that managed to increase stability but did not contribute much to power consumption, which gives the upper hand to the upgraded numerical approach in that aspect. The numerical approach makes it easier for the gait designer to generate a gait since no separate phases need to be handled differently unlike the closed-form approach which separates single and double support phases. However, the superiority of the numerical approach comes at the expense of a lengthy computational time (almost 12 times that of the closed-form approach), which suggests its usage for robots with heavy-duty expensive computer boards and whose link masses and speed are likely to put weight on the energy optimization criteria. The lighter upgraded closed-form approach can be used for robots with small masses and sizes with relatively humble computational capabilities.
Footnotes
Declaration of conflicting interests
The author(s) declared no potential conflicts of interest with respect to the research, authorship, and/or publication of this article.
Funding
The author(s) received no financial support for the research, authorship, and/or publication of this article.
Appendix
Variable A
