1. Introduction
Mobile ground robots emerged as an alternative to several tasks originally performed by humans, such as surveillance, reconnaissance, entertainment, personal services, patrolling, and industrial automation, to cite a few [
1]. Particularly, nowadays, interest is focused on tasks involving complex and potentially hazardous situations such as planetary exploration, emergency rescue operations, and, more in general, intervention in extreme environments [
2].
Mobile ground robots in the literature differ regarding locomotion, surrounding perception, and control methodologies. Focusing on locomotion, they can be grouped into the following:
Wheeled robots;
Tracked robots;
Legged robots;
Wheeled robots are characterized by high speed, high energy efficiency, and a cost-effective design, so they are widespread in industrial, service, and delivery applications on mostly flat surfaces [
1]. Conversely, tracked robots are more appropriate for movements on soft and irregular terrains because they have a larger surface in contact with the ground, and they are also able to climb over obstacles [
3]. Legged robots show superior mobility compared to wheeled and tracked robots since they can navigate through any terrain, climbing rocks and rough surfaces like humans and animals [
1,
4,
5]. These extraordinary capabilities and their versatility that allow them to operate in different environments make them the preferred choice for search and rescue [
6], exploration [
7], agriculture [
8], or operations in dangerous environments [
9,
10,
11] despite their high complexity and cost. Finally, some hybrid robots combine these locomotion types, being equipped with legs and wheels or tracks as paws. These robots have the same adaptability and agility as legged robots because they can easily overcome obstacles and perform different types of gaits on uneven terrains and, at the same time, can achieve high speed with great efficiency on flat surfaces [
12]. Nevertheless, the complexity of the design limits the optimality in both aspects [
13].
The choice of using bioinspired paws or hybrid locomotion depends on the particular type of terrain in which the robot is supposed to operate. Still, the main parameter that influences the performance of a legged robot is the number of legs [
1], and they can be one of the following:
Bipedal robots are mainly humanoid robots designed to replicate many human abilities, such as grasping, handling objects, or human-like sensing, and locomotion is just one of the several tasks these robots are capable of performing. Nevertheless, many humanoid robots can run, jump, climb, and move in any environment with extreme agility [
1]. The disadvantage of bipedal locomotion is the intrinsic instability of this gait, which is why humanoid robots require very complex control algorithms to maintain balance even when they do not move.
Quadrupedal robots are the best-performing walking robots in terms of speed and payloads [
1]. Moreover, they have the advantages of allowing different gait types and being statically stable when they are not moving. Nevertheless, they still require very complex control algorithms since they possess many degrees of freedom that must be coordinated, and most performing gaits need dynamic walking control since only two limbs are in contact with the ground.
Hexapod robots, instead, always have three limbs in contact with the ground, so their gaits are stable, making walking control much simpler despite the increased number of degrees of freedom to coordinate [
14,
15]. This stability makes them particularly suitable on uneven or slippery terrains where bipedal or quadrupedal robots struggle to find a stable gait. Furthermore, their redundancy allows them to operate by still using quadrupedal locomotion if one or two legs are not functioning [
1], which is a significant advantage for operations in places difficult or unsafe to reach for humans. Robots with more than six legs do not have particular advantages over hexapod robots apart from the increased variety of gaits and the improved redundancy, but these come at the cost of more complex control due to the additional degrees of freedom.
2. State of the Art
In the field of ground robots, one of the crucial benefits of hexapod robots is their outstanding ability to operate on virtually any terrain. An essential aspect is represented by the detection and mapping of terrain shape and unevenness. Common approaches for ground classification can be classified as Visual-Perception-based, Depth-Perception-based, or Tactile-Perception-based, as reported in [
16], where all three families of sensors are combined in order to achieve improved accuracy. Visual-Perception-based systems take advantage of image processing for ground classification, starting with cameras. In [
17], an online terrain-classification system for hexapod robots capable of adapting energy-efficient gaits is presented, which is based on feature extraction and SVM classification of a monocular camera output, achieving up to 90% accuracy on terrain images. Another example is reported in [
18], where an algorithm based on neural networks is used to identify the terrain from an RGB image to define surmountable obstacles and zones. Vision-based terrain mapping is also used in [
19], where visual sensors are used to detect the terrain shape using point clouds and unsupervised learning techniques and to control the interaction between two collaborative robots. Depth-Perception-based classification relies on the use of depth data, usually in addition to images from cameras as presented in [
20] with the purpose of characteristics extraction and objects or plane identification. Finally, Tactile Perception relies on using sensors such as IMU, pressure, or torque sensors to perceive the presence of the ground, usually thanks to the measurements (forces and torques) at the tip of the leg as reported in [
21]. In this paper, a terrain map is considered as known since it is not the aim of this research.
In order to exploit the potential of hexapod robots in uneven terrain conditions fully, the interaction of their paws with the ground must be taken into account both in the robot’s mechanical design and the implementation of the control algorithm [
15,
22] to properly provide counteraction to terrain-reconstruction errors. For this reason, the most advanced control techniques of hexapod robots not only include a kinematic and dynamic model of the robot itself but also consider the forces that the paws exert on the ground. They use this information to detect contact, consider terrain deformation, and avoid slipping. Among all the possible improvements that are introduced by adding a model of interaction with the ground to the control algorithm, contact detection is the most useful since it allows the robot to maintain balance on uneven terrains and in the presence of obstacles because, by knowing which paws are in contact with the ground, the robot can adjust its posture and adapt its gait to accommodate terrain unevenness, distributing the weight better and improving stability [
22].
In addition, real-time feedback on contact detection reduces the time needed for each leg to search for contact with the ground, making the transition between consecutive steps faster and smoother.
As already introduced, contact detection can be achieved by directly measuring the force between each paw and the ground with pressure or force sensors or by estimating this force by measuring the torque or the current of the motors of each joint of the legs [
15]. The first approach gives a more accurate measurement of the contact force, but it requires placing sensors under the robot’s paws, adding complexity to the geometry of the paw [
23,
24,
25,
26,
27,
28]. In addition, this strategy relies on components that continuously receive impact forces, and they might easily break. Conversely, estimating the contact force by measuring the motors’ torque is a less accurate but more reliable approach. Furthermore, in some scenarios, position feedback can be sufficient to accurately identify terrain presence and maintain horizontal positioning at all times [
29,
30,
31].
In the field of legged robotics, companies offer proprietary solutions, such as Boston Dynamics [
32], or others are more focused on academic research, like Robotis [
33] and Trossen Robotics [
34]. From a software perspective, academic research tends to favor the use of open-source solutions to provide greater access and control over the robot’s implementation. In this context, various frameworks enable the programming of hexapod robots. In particular, NUKE [
35] is open-source software designed specifically for the control of hexapod robots. It is optimized to manage the locomotion and kinematics of these robots through an intuitive interface and predefined configurations that facilitate programming and customization. Compared to more general-purpose solutions like ROS2 [
36] or ArduPilot [
37], NUKE provides predefined and customizable solutions that reduce complexity and accelerate the development of hexapod projects. This makes it a convenient choice, although its support is less extensive and its updates are less frequent compared to other solutions, particularly ROS2.
Based on the previous discussion, the main contribution of this work consists of a deep analysis and extension of the inverse kinematics formulation of NUKE to include the orientation and height of the robot’s body from the ground as additional input to the position of the robot’s leg’s end effectors. Moreover, this paper proposes a comprehensive architecture for handling terrain irregularities that leverages the extended functionalities of NUKE and estimates joint torques in the event of individual leg contact with the ground using a dynamic hexapod model. The standard implementation of NUKE suffers from the main limitation that most multilegged robot-control software has. While perfectly able to move the robot smoothly and adjust stride correctly through a gait engine, they can generally not interact with anything other than flat, continuous, obstacle-free terrain [
38]. This paper aims to extend the advantages of the NUKE code in the presence of non-flat, non-continuous, irregular terrain. In particular, the underlying objective is to develop a kinematic model that can account for the terrain shape and location and to improve this analysis further to understand how the robot’s physics interacts with the presence of the ground. By utilizing this estimate alongside the one provided by the robot’s servomotors, a feedback control system was developed without the need for sensors at the ends of the legs. In order to implement and test the proposed architecture, PhantomX AX Metal Hexapod Mark II from Trossen Robotics
TM [
39], shown in
Figure 1, is considered. It is a versatile, inexpensive, and lightweight robot. Moreover, it is fully programmable, compatible with NUKE, and based on open-source hardware. It has neither force feedback sensors on its legs nor an IMU in its standard configuration, but it mounts 18 Dynamixel
TM AX-12A Smart Servomotors [
40] that can provide feedback on position and load estimates.
The novelty of this work is represented by the development of a control algorithm for hexapod robots that can maintain the robot’s body horizontally regardless of the slope and the unevenness of the terrain. This goal can be achieved without the addition of any sensors on the robot’s feet because the estimation of the motors’ torque allows it to detect contact with the ground, and by knowing the angles of each joint, the robot’s pose is reconstructed through inverse kinematics. In addition, this control algorithm extends the functionality of NUKE, an open-source software compatible with different kinds of hexapod robots and widespread in this field, making this work helpful for other studies involving hexapod locomotion.
In
Section 3, the kinematic model and the procedure to account for ground shape are described. In
Section 4, the dynamic model used to estimate the torque at each motor is proposed and numerically validated. In
Section 5, the novel architecture system comprehensive of a compensation algorithm is presented, and finally, in
Section 6, experimental results in different scenarios are reported.
3. Locomotion Control
Locomotion control of the hexapod robot is mainly accomplished through the direct command of its legs’ endpoints. Leg endpoints are defined as the 3D coordinate points located at the extremities of each leg, as shown in
Figure 2.
Since legs are 3-DOF systems that lead to the endpoints, it is possible to attain full control of a leg by imposing its endpoint position and employing an inverse kinematics engine to calculate the associated servomotor angles.
Such control architecture offers the advantage of collapsing the description of each leg configuration to a single point position in space, leading to much simpler and clearer handling of the robot’s movement.
The position that the robot assumes at the deployment state is called the neutral position, and the associated endpoint coordinates are hardcoded into the robot controller software. This position represents a neutral state that the kinematic engine will use as a reference to build its walking gait.
3.1. Endpoints Handling
The coordinate systems employed in the kinematic analysis of the robot are presented in
Figure 3. The
global coordinate system is fixed at terrain level at 0,0,0 coordinates and will be used to account for the robot’s position with regard to the terrain and the environment. Therefore, for the first iteration, the transformation matrix for the global-to-body coordinate system
(alias:
) is as shown in (
1):
where ‘SP’ is the
starting position. Note that
should be the initial robot height and must be consistent with the neutral position endpoint coordinates.
The body coordinate system and the legs coordinate systems instead move alongside the robot’s body and are used to both describe the robot’s orientation and solve the inverse kinematics for endpoint position and servomotor angles.
The transformation matrix that binds the leg c.s. and the body c.s.
(as:
) is defined as (
2):
where in (
2),
and
are the joint positions in the body c.s., from which it is inferred that
is unique for each leg as each leg has a different joint position.
Once the desired endpoint position has been defined, servomotor angles can be assessed. The convention used in the kinematic analysis is shown in
Figure 4, where
represents the servomotor orientation and
,
, and
represent the coxa, femur, and tibia servomotor angles, respectively.
By expressing the desired endpoint position in the leg coordinate system, eventually, through (
2), the servomotor angles can be calculated through (
3)–(7):
where in (
3)–(7),
is the position of the desired leg endpoint in the leg coordinate system, and
,
, and
are the lengths of the coxa, femur, and tibia, respectively. The endpoint positions are defined in the body coordinate system; therefore, their significance is fully derivative of the position and orientation of the robot’s body. This means that every movement that the robot’s body is instructed to make can be immediately transposed to a relative displacement of the endpoints; the complete kinematic model can be built based on that assumption.
A gait engine is a subroutine of the locomotion algorithm that handles leg synchronization: in general, any pedal locomotion divides each leg in either a pushing or swinging state in a fixed order in such a way to allow for repetitive, continuous movement. The gait engine is responsible for assigning the swing and push roles as well as the direction and amount of space to cover for each iteration tick. The gait engine employed is not fundamental to describe the desired formulation and will not be discussed as descriptions are already available in the literature (the gait engine employed in this treatment is the one provided by NUKE). Therefore, from the user input comprising the x-speed, y-speed, and z-axis rotation speed, the gait engine provides the movement data that the robot is supposed to follow, and the kinematic problem is to find the related endpoint displacement.
In order to solve the kinematic problem, it is imperative to be able to describe the robot’s position and orientation at each iteration step by taking into consideration all the movement data provided by the gait engine and by direct command of the user (the user is supposed to be able to bypass the gait engine instructions to apply direct control of the robot’s pose at each iteration step).
That is performed by building the
transformation matrix at each
ith iteration step (as
) as shown in (
8):
where in (
8),
is the translational transformation matrix holding data about the movement instructions coming from the gait engine. It is built as shown in (
9) and reconstructs the robot’s position as if it were just under the influence of the gait engine alone:
In which
is the transformation matrix representing the
ith step movement due to the gait engine instructions. It is made of two contributions, as shown in (
10):
In which
is the component related to the translational movement and
is the one related to the z-axis rotation. Those are defined in (
11) and (
12), respectively:
where in (
11) and (
12),
,
, and
are the gait engine movement instructions for the
step x-axis displacement, y-axis displacement, and z-axis rotation, respectively.
is the transformation matrix holding the user-imposed translational movement data of the robot’s body, defined as in (
13):
, , and are the transformation matrices holding the user-imposed orientation of the robot’s body, being the z-axis rotational matrix, y-axis rotational matrix, and x-axis rotational matrix, respectively.
is the terrain-compensated reorientation matrix addressing additional body displacement due to terrain shape. It depends on the position of the robot’s body in the terrain environment. It can either be given by user input or computed in real-time based on the terrain shape in the robot’s surroundings. Our objective is to assemble this matrix automatically by employing a terrain-tuning algorithm that takes as its only input the terrain elevation function , which can again either be given as user input (assuming perfect knowledge of the terrain shape) or constructed by an estimation architecture. is an identity matrix for completely flat terrains.
Therefore, the entire movement comprising all contributions that the robot’s body goes through at the
ith iteration step is represented by the transformation matrix calculated as in (
14):
Due to friction, the
pushing legs endpoints are fixed to the terrain; therefore, their global position should not change between iterations. This means that if the body moves as described by (
14), then the relative position of the endpoints should change as (
15):
This way, it is possible to solve the kinematic problem for the
pushing legs endpoints. Note that since (
15) is built recursively, it needs starting values. These are the neutral position endpoints, which is why their coordinates are hardcoded into the control software. The
swinging legs endpoint positions are defined as (
16):
where
,
, and
are the endpoint coordinates of the neutral position. The reason why (
16) refers to the neutral position endpoint coordinates and addresses
and
instead of
and
is because of the core difference between (
8) and (
14): instead of building the endpoint transformation from the previous endpoint position, the gait engine now needs to displace the leg in such a way that the swinging stride motion is obtained. This means that the movement data coming from
and
are no longer about increments of movement but effective displacements from the neutral position. The gait engine should return these values when assessing the
swinging legs endpoints.
To account for terrain presence and ensure that the leg will always be over the terrain height while swinging, the correction shown in (
17) should be applied:
where
is the
elevation function of the terrain.
Once the global coordinates of the swinging legs endpoints are found, the body-centered coordinates are found as in (
18):
Completing the kinematic problem assessment.
3.2. Terrain Compensation Algorithm
The objective of this section is to develop a way to orientate the body pose of the robot in such a way that while moving the robot freely on the ground, its body becomes ‘isolated’ with respect to the ground itself.
Assuming perfect knowledge of terrain geometry in terms of angular and discontinuity interface position would not be realistic nor aligned with our objective of developing an adaptive algorithm. Our purpose is the design of an algorithm able to deal with any terrain just relying on the elevation function, which could be measured by sensors mounted on the robot itself, but this is not the purpose of this work [
16,
41].
First of all, it is important to unequivocally define the ‘body isolation’ condition: this can be achieved by defining a set of points in the robot’s body and then considering the height of these points with respect to the ground as a way to evaluate the body’s relative position to the terrain. A possible approach is to ask for those points to maintain a distance from the ground as close as possible to the one defined by
in (
1). If these points of interest are correctly chosen in order to represent the vertices of the robot’s body, the entire base should follow the terrain profile and prevent unwanted situations like the ones discussed beforehand.
With the proposed algorithm, the robot’s body will be able to position itself in such a way that it complies with the terrain geometry no matter the harshness.
In the algorithm presented, six points are selected in the locations of the robot’s shoulders, as shown in
Figure 5.
The main assumption of the compensation model is that the robot will be able to position itself in the optimal pose by moving from its horizontal pose defined by
with three degrees of freedom only: a first displacement in the z-direction followed by a rotation around its body c.s. y-axis and a final relative rotation around its body c.s. x-axis. In transformation matrices, this is described by (
19):
where
is the z-axis rigid translation matrix defined as in (
20):
and
are the rotation matrices defined as in (
21) and (22):
where in (
21) and (22),
is the angular rotation around the body c.s. y-axis and
is the angular rotation around the body c.s. x-axis.
From the global coordinate system, the joint positions after the terrain reorientation are (
23):
Since we want our points to have relative heights as close to
as possible, we can build an algorithm that minimizes the total relative height quadratic error. It is accomplished by accounting for each point, shown in (
24) with reference to (25):
The problem is a multivariable optimization problem with equality constraints coming from trigonometric function consistency, solvable by writing the Newton–Euler equations with Lagrangian multipliers [
42]. The formulation obtained and reported in Equation (26) comes from adjoining the equality constraints in Equation (25) to the cost function in Equation (
24):
The necessary conditions hold for the minimum [
42] as
.
The Lagrangian function is differentiable, and its gradient is calculated by taking the partial derivatives of Equation (26).
In order to find the solution to , M-V-O-P numerical methods need to be employed. In this situation, given that the cost function is quadratic, it is possible to effectively employ the steepest descent algorithm to iterate and find the solution very quickly and with a relatively low computational cost.
Having already defined the gradient of the Lagrangian, the steepest descent algorithm is implemented as in (27):
With the stopping condition being . In (27), the parameter represents the adjustment index of the increment to the next-iteration solution. Generally, a of is good enough to obtain convergent solutions in a few iterations in most general applications.
This method ensures good performances in most terrain situations, only experiencing non-convergence problems in extreme scenarios. As shown in
Figure 6, with reasonable weight (
) and tolerance (
), the solution is generally found very quickly.
The robot’s stability in the current formulation is ensured through NUKE’s original gait engine, which arithmetically enforces the robot COG to always stay within bounds. Indeed, the only gait types accepted by the algorithm are those that allow the hexapod robot to maintain static stability in all intermediate positions during movement, with the “less-redundant” one being the tripod gait, where three legs are moved at each time, but the algorithm always ensures that the support triangle bounds the COG projection.
Since the problem was defined in general terms, the algorithm can run even in situations where rough interfaces are present, moving the robot in such a way as to allow for a smooth transition between angular interfaces and navigation over non-continuous terrains. An important assumption considered in this analysis is the simplification of the terrain behavior: an ideal undamped and rigid terrain is assumed, and the potential slipping of the leg upon exceeding the static friction limit is neglected since a purely geometrical approach is proposed.
In the scenario of a steep ramp given a full horizontal speed input, the robot can smoothly go from being completely horizontal to adapting to the terrain inclination, as shown in
Figure 7 and
Figure 8.
Since the algorithm runs on the elevation function only, realistic terrains defined through conventional discrete models [
43] can be used without particular adjustments.
5. Closed-Loop Control
A closed-loop-control approach is essential to obtain stable, robust movement throughout the entire range of movement tasks that the robot will be subjected to. After a few steps, a completely feed-forward approach may lead to positioning errors related mainly to robot–interface mismatching between reality and expected values, which would translate to grip losses and other unwanted behaviors to avoid in the presence of uneven terrain.
The two major situations to avoid are the cases where the feed-forward locomotion-control system expects the terrain to be higher and, therefore, leaves the leg hanging. The case where it expects it to be lower and, therefore, pushes the body back in an overstepping action destabilizes the entire robot pose. These situations are bound to happen due to either terrain mismodeling or desynchronization between the expected behavior from the simulation environment and the actual robot motion, which is mainly due to the increasing drift between the real and expected position of the robot as it accumulates positioning errors due to all non-ideal behaviors and performances coming from its hardware and components. Note how both situations happen in the leg-lowering part of the swing phase only, meaning a feedback control algorithm acting on real ground touching just needs to be called during that movement section.
The feedback control system works by comparing the expected value of the actuators’ torques coming from the dynamic model with the actual sensed torques coming from the sensors system.
By reading the actuator position and speed and estimating the body movement from
, it is possible at each iteration to build the estimated
and
state vectors, to which the algorithm immediately calculates the
and
components as defined in (
49) and (50), with these being the only actual dependencies.
Once these two values are stored in memory, the lowering legs’ sudden terrain touch can be simulated in the dynamic model by simply interacting with the
values defined earlier in (
42) and (43). The
boolean represents the grounded state of the
ith leg’s endpoint; therefore, by temporarily setting it to one and building the
and
constraint matrices, it is possible to obtain the hypothetical terrain-reached torques for all actuators through (46). This is an easy, relatively CPU-light way to obtain full references for the leg–terrain touch situations.
If there is a sensible correspondence between the expected torques and the sensed ones, then the terrain is considered reached for that particular leg, and its movements are stopped. This accounts for the overstepping part of the problem, while it may still be possible for the legs to reach their desired end positions when no terrain has been sensed.
In order to solve the ‘leg-hanging’ problem, it is only necessary to lower the expected altitude of the desired leg endpoint position (in the employed algorithm, the gait altitude instruction is lowered by 1 cm each time), , and recompute the needed servomotor angles. This can be obtained by lowering the legs until the terrain is touched and the previous condition is met, effectively assuring that the legs reach the ground and stop right before moving to the push phase.
Finally, since the servomotor stopping condition is changed to sensed terrain touch, the lowering leg endpoints will probably differ from the ones expected by the locomotion system instructions. Therefore, the new positions need to be updated by employing forward kinematics tools such as the
,
, and
transformation matrices derived through (
31)–(33).
A scheme summarizing the leg-handling system is shown in
Figure 13. An implementation example of the closed-loop-control solution is presented in Algorithm 1.
Algorithm 1: Lowering-leg-control algorithm pseudocode. |
|