Next Article in Journal
A Comparative Study of Differential Quadrature Methods for METE Nanobeam Vibrations
Next Article in Special Issue
Analytical MPC Algorithm Using Steady-State Process Model
Previous Article in Journal
Anomaly Detection in High-Dimensional Time Series Data with Scaled Bregman Divergence
Previous Article in Special Issue
Control of a Mobile Line-Following Robot Using Neural Networks
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Evaluation of PID-Based Algorithms for UGVs

1
Engineering Department, School of Sciences and Technology, University of Trás-os-Montes and Alto Douro (UTAD), Quinta de Prados, 5000-801 Vila Real, Portugal
2
GECAD—Knowledge Research Group on Intelligent Engineering and Computing for Advanced Innovation and Development of the Engineering Institute of Porto (ISEP), Polytechnic Institute of Porto (IPP), 4200-465 Porto, Portugal
3
Department of Mechanical Engineering, Association for the Development of Industrial Aerodynamics (ADAI), University of Coimbra, Rua Luís Reis Santos, Pólo II, 3030-788 Coimbra, Portugal
4
Coimbra Institute of Engineering (ISEC), Polytechnic Institute of Coimbra (IPC), Rua Pedro Nunes-Quinta da Nora, 3030-199 Coimbra, Portugal
5
Institute of Telecommunications, Department of Electrical and Computer Engineering, University of Coimbra, 3004-531 Coimbra, Portugal
6
Department of Electronics and Telecommunications, Polytechnic of Torino, Corso Duca Degli Abruzzi, 24, 10129 Torino, Italy
7
Institute for Systems and Computer Engineering-Technology and Science (INESC TEC), Rua Dr. Roberto Frias, 4200-465 Porto, Portugal
8
Institute of Systems and Robotics, Department of Electrical and Computer Engineering, University of Coimbra, Rua Silvio Lima-Polo II, 3030-290 Coimbra, Portugal
9
Institute of Electronics and Informatics Engineering of Aveiro (IEETA), University of Aveiro, 3810-193 Aveiro, Portugal
10
Intelligent Systems Associate Laboratory (LASI), University of Aveiro, 3810-193 Aveiro, Portugal
*
Author to whom correspondence should be addressed.
Algorithms 2025, 18(2), 63; https://doi.org/10.3390/a18020063
Submission received: 29 December 2024 / Revised: 16 January 2025 / Accepted: 21 January 2025 / Published: 24 January 2025
(This article belongs to the Special Issue Algorithms for PID Controller 2024)

Abstract

:
The autonomous navigation of unmanned ground vehicles (UGVs) in unstructured environments, such as agricultural or forestry settings, has been the subject of extensive research by various investigators. The navigation capability of a UGV in unstructured environments requires considering numerous factors, including the quality of data reception that allows reliable interpretation of what the UGV perceives in a given environment, as well as the use these data to control the UGV’s navigation. This article aims to study different PID control algorithms to enable autonomous navigation on a robotic platform. The robotic platform consists of a forestry tractor, used for forest cleaning tasks, which was converted into a UGV through the integration of sensors. Using sensor data, the UGV’s position and orientation are obtained and utilized for navigation by inputting these data into a PID control algorithm. The correct choice of PID control algorithm involved the study, analysis, and implementation of different controllers, leading to the conclusion that the Vector Field control algorithm demonstrated better performance compared to the others studied and implemented in this paper.

1. Introduction

Unmanned ground vehicles (UGVs) have received significant attention due to their ability to operate in unstructured and dynamic environments where human intervention is limited or hazardous. These robotic platforms are widely used in applications for unstructured environments, such as in agriculture, where the current literature reports the application of UGVs in specific agricultural tasks [1,2]. Additionally, in forestry, although advancements are more limited compared to agriculture, the literature already highlights some progress, as demonstrated in [3,4]. The navigation of UGVs in unstructured outdoor environments has been challenging due to the presence of adversities/unpredictable factors such as lighting, shadows, obstructions, dynamic obstacles, and rugged or demanding terrains [5,6]. Given these constraints, the focus of research by many investigators in the field of mobile robotics has been on developing UGVs capable of navigating autonomously and efficiently.
Such autonomous systems in challenging environments require a computational component to enable UGVs to perform trajectory planning. The ability of a UGV to plan a trajectory that not only reaches a target destination but also avoids obstacles with time and efficiency guarantees are basic functions that UGVs must possess, regardless of the application scenario. We can identify three types of controllers commonly used in this field: classical control, referred to as Proportional, Integral, and Derivative (PID); intelligent and adaptive control (Fuzzy); and predictive control [7]. However, for the work addressed in this article, the PID controller is used.
Thus, the autonomous navigation technology of UGVs in unstructured environments involves trajectory planning and control, precise positioning, and other functions.
The current literature reveals the existence of various navigation systems, with the most commonly used being the real-time kinematic global satellite navigation system (RTK-GNSS). This type of system achieves centimeter-scale accuracy in satellite positioning, but requires a clear line of sight [8]. In addition to this navigation system, other, less predominant systems also appear in the literature, which collects different types of sensory data. These systems include GNSS/INS, which result from the combination of a Global Navigation Satellite System (GNSS) and an Inertial Navigation System (INS) [9,10]; GNSS/VISUAL/INS systems, which combine GNSSs, visual information, and INSs [11]; GNSS/VISUAL/IMU/MAP systems [12]; and others.
For the work in question, the GNSS-RTK/INS navigation system was used, which combines data from GNSS + RTK + IMU sensors to obtain the position, as well as a magnetometer to determine the heading or yaw (referring to the robot’s rotation along the Z-axis of the UGV).
Thus, in this article, a set of PID control algorithms, referred to as follows, is evaluated and studied:
  • ON–OFF controller;
  • PID Heading controller (PID-H);
  • PID Cross Track Error controller (PID-CTE);
  • PID Cross Track Error + Heading controller (PID-CTE + H);
  • PID Vector Field (PID-VF).
Thus, this article aims to demonstrate which of the implemented algorithms achieves the most efficient behavior for UGV navigation in unstructured environments (in this case, the unstructured environment under study consists of a forest environment).
This paper is organized as follows: Section 1 introduces the motivation behind this work. Section 2 presents topics related to the state of the art of PID controllers. Section 3 details the methodology, including a description of the robotic platform used and its integrated sensors, the PID control algorithms with a detailed explanation of each one employed, and, finally, the performance evaluation metrics. Section 4 shows the results obtained through real-time experiments and the evaluation of the proposed PID control algorithms. Section 5 concludes with an overall analysis of the work carried out.

2. Related Work

2.1. Advantages and Disadvantages of Different Control Methods

The PID controller is one of the most widely used methods in UGV control systems due to its simplicity, robustness, and effectiveness in adjusting control variables such as speed and direction. In addition to this type of control, the literature also highlights three others: the ON–OFF controller, fuzzy controller, and Model Predictive Control (MPC).
The ON–OFF controller is particularly simple and practical to implement, such that quick response capabilities can be realized in systems with on-off inputs, and thus the ON–OFF controller is widely employed for binary actuations. Despite this, it is power hungry and imprecise and therefore not suitable for applications that demand control with optimal or continuous control [13].
The PID controller, with its three parameters, can control the steady-state and transient responses nicely and provides simple yet effective control solutions for a wide range of control problems. Nowadays, they are widely used in a variety of industries because of their simple structure and intuitive understanding of the controller principle, as compared to other types of controllers. As described, the behavior of PID controllers depends on these parameters. Yet, the potential vulnerability of their robustness and simplicity can make them challenging to parameterize [14].
The fuzzy controller has significant benefits in energy consumption and convergence time. It also affords a more stable response across variable conditions in contrast to conventional approaches that may be responsive to initial torques and to inhomogeneity in friction. Despite these benefits, the fuzzy design has a number of problems, such as the accuracy being affected by the actuation deadband and the computational complexity, meaning that the design frequently needs to be simplified [15].
Model Predictive Control (MPC) is a powerful control architecture that uses dynamic models to predict and optimize control actions within a time window. It can accommodate input and output constraints, making it ideal for complex and dynamic systems, such as industrial process level control. However, the validity of MPC depends upon the validity of the system models, and the absence of this validity may lead to suboptimal behavior. Moreover, real-time optimization procedures may be computationally heavy, resulting in implementation difficulty [16].
PID controllers are widely preferred due to their simplicity, readability, and ability to handle both steady-state and transient responses. Although more sophisticated controllers such as fuzzy logic and Model Predictive Control (MPC) have specific advantages, e.g., a better energy efficiency or optimization for dynamic systems, they generally come with disadvantages, e.g., increased complexity or larger computational needs. Table 1 shows the advantages and disadvantages of each type of control.

2.2. Comparative Approaches to the Use of PID Controller Algorithms in UGVs

Several studies and reviews are available in the literature addressing UGV navigation methods, whether in structured or unstructured environments. The work conducted by Ji Y. et al. demonstrates the application of a UGV in unstructured environments, where the A-STAR algorithm was used, enhanced with improvements in the heuristic function to achieve shorter paths [17]. In [18], the authors proposed a method involving a hierarchical adaptive control strategy for UGVs, using a PID to estimate the yaw moment and PSO optimization to handle structural uncertainties, distributing the yaw moment among the motors. Sun Y. et al. present a trajectory-following PID control design for a three-wheeled UGV, addressing lateral directional control, vector-field-based orientation, and sensor fusion using a Kalman filter [19]. In [20], the authors introduced a method based on vector differences and self-adaptive mechanisms for PID tuning, aimed at minimizing human intervention in the adjustment of PID controllers across a diverse and extensive set of problems/tasks. To achieve this, an innovative approach based on the Differential Evolution algorithm with Success-Based Particle Adaptations (DEPA) was employed. This algorithm utilizes a memory mechanism to autonomously and efficiently adapt control parameters.
Moreover, modern control techniques also stand out in complex systems such as Markov jump systems. For instance, Vijayakumar et al. [21] proposed an approach based on a Proportional–Integral Observer (PIO) and disturbance rejection techniques with IEID, as well as a Smith predictor for systems with input delays and state-dependent nonlinearities. This method employs linear matrix inequalities (LMI) and Lyapunov stability theory to ensure robust output tracking with disturbance rejection. Similarly, Song and Jin [22] presented a tracking control approach based on observers for Markov jump systems with partially known transition rates, utilizing LMI and stochastic stability theory. This method focuses on reference control and ensuring stability for systems with undefined transitions. Although this work targets specific transition rate conditions, it highlights the importance of observers in improving accuracy and stability in uncertain systems.
However, Gomathi N. et al. introduced an adaptive trajectory planning framework where a UGV equipped with LIDAR and a camera was used to monitor agricultural terrains. For trajectory planning, they proposed the HSAStar hybrid algorithm (Hybrid SLAM and A Star), which combines SLAM and A* to allow the UGV to continuously monitor the path while mapping [23]. Farag W. et al. developed a PID controller designed to improve the capability of autonomous cars to perform maneuvers on pre-calculated tracks. They proposed three approaches to design and tune the controller’s hyperparameters, using the CTE as input and generating steering commands as output. Simulations on complex tracks, including sharp curves, were used to evaluate the controller’s performance at different speeds [24]. In [25], the authors proposed a PID controller to address the trajectory tracking problem in mobile robots with differential kinematics. The developed method consists of a trial-and-error technique with six tuning parameters to allow the robot to follow a desired trajectory. The controller was designed to handle the non-linearity of reference trajectory tracking and adjust the speeds of the robot’s DC motors.
Additionally, Akopov et al. [26] adopted an algorithmic optimization approach for autonomous systems by introducing a simulation-based optimization technique for autonomous transport systems. They implemented a Real-Coded Genetic Algorithm with Scalable Non-Uniform Mutation (RCGA-SNUM). This method was designed to minimize traffic accidents through the simulation of autonomous vehicles on an Artificial Multi-Connected Road Network (AMCRN).
Despite extensive study on PID control for UGVs, issues persist in its adaptation to dynamic and unstructured situations. These issues encompass the management of nonlinear dynamics resulting from fluctuating terrain conditions, the assurance of dependable trajectory tracking amongst external disturbances, and the achieving of real-time sensor fusion for accurate control. The design is further complicated by the need for scalability across various workloads and the minimization of latency in resource-constrained systems.

3. Methodology

3.1. System Description

The UGV used for the development of this work is an internal combustion tractor called Green Climber LV600, manufactured by MDB in Abruzzo, Italy, as illustrated in Figure 1a. This platform is equipped with a sensory box (referred to as Sentry), as shown in Figure 1b, which integrates a variety of sensors and hardware elements. This setup is connected to the tractor, thus providing a set of features for autonomous navigation in unstructured environments.
Thus, the goal is to enable the above robotic platform to perform autonomous trajectory navigation. The trajectories are defined by a set of Cartesian points, and the objective is for the robot to execute these trajectories using a PID algorithm, where the control variables are derived from a navigation system.
The adopted navigation system, which will collaborate with the PID algorithms, is based on GNSS-RTK/INS, where the PID control algorithms will receive data on the position and orientation/heading of the UGV. The position and heading values are provided by a sensor located on top of the sensory box, called Duro Inertial. The Duro Inertial system is ideal for navigation systems as it consists of sensors such as GPS, an accelerometer, a gyroscope, and a magnetometer, and through the combination/fusion of these, it is possible to obtain the position and orientation. This sensor, when connected to the RTK system, can provide a position accuracy of between 1 cm and 1.5 cm [27].
The system that inputs data into the PID controller can be seen in the diagram presented in Figure 2. The robot’s position, whose origin/acquisition is based on work developed in [28], is essentially obtained by combining data from the GNSS + RTK system, which provides the latitude and longitude, along with an IMU that gives information on the robot’s acceleration and velocity in three dimensions. These data are then aggregated in a Kalman filter, which allows, with some confidence, to provide the robot’s x and y position. The robot’s heading, which is derived from work developed in [28,29], comes from a three-dimensional magnetometer, and through the magnetic fields, it is possible to obtain the heading in Cartesian space (which, in this case, refers to the yaw of the UGV). However, before processing the magnetometer data, it undergoes a filtering process, where a Raised Cosine Moving Average (RCMA) filter is applied to minimize the noise present in these types of sensors. After filtering, these data are integrated with IMU data to compensate for inclinations in the terrain.

3.2. Control System and Controller Selection for UGV Navigation

The robot control system is a MIMO (Multiple Inputs and Multiple Outputs) system equipped with various controllers. Due to the lack of knowledge regarding the speeds of each track, its control is achieved by obtaining the position and orientation of the UGV. Through the ROS platform, it is possible to acquire both the position and orientation of the robot via various published “topics”, as well as the linear and angular velocity of the robot through the “cmd_vel” topic. Since it is not possible to directly control the UGV’s speed, we assume the velocities as control variables but treat them as indicators to understand the UGV’s movement.
Given that we are dealing with a differential structure, it only has two axes, x and z, with the x-axis corresponding to linear velocity and the z-axis to angular velocity. To ensure system safety, software protection has been included where the sum of these two components cannot exceed 1. In other words, 1 is considered the system’s maximum speed, and 0 is the minimum speed. Table 2 provides several examples illustrating how the robot should move based on the values obtained from the “cmd_vel” topic.
The “controller” publishes the commands, but the voltage applied to the UGV is controlled by a driver managed by the “microcontroller”. The microcontroller operates as a state machine, adjusting the voltage sent to the tracks based on the “cmd_vel” topic.
Initial tests established the maximum and minimum voltage limits for the reliable operation of the solenoid valves and tracks. These tests involved gradually applying voltage and observing the effects on speed, steering, and stability. Using the results, functions were created to model how the solenoid valves and tracks respond to voltage variations. This allowed the development of rules to optimize the UGV’s performance and ensure efficient operation.
The references R1 and R2 are desired values from the UGV’s trajectory planning system, serving as inputs for the controllers. Errors e1 and e2 are calculated as the difference between desired and actual values. The controllers send corrections to the microcontroller, which adjusts the tracks to align the UGV’s movement with the planned trajectory.
The UGV’s various controllers can be selected based on the operating circumstances. For example, a controller can be activated to maximize traction and stability on inclined or slippery terrain, thereby improving safety and efficiency. Additionally, the ability to dynamically switch controllers helps reduce environmental impacts, such as choosing a gentler controller in sensitive areas where soil and vegetation preservation is critical, thereby avoiding inevitable damage to the surrounding ecosystem. The use of multiple controllers in forestry operations is a significant innovation in this context. This methodology provides technical advantages and enhances the sustainability of operations in challenging environments, showcasing the technology’s ability to tackle diverse challenges while promoting more ethical and effective practices in navigating these machines.
The next section discusses different types of controllers developed for controlling the robot, such as the ON–OFF controller and various PID controllers for managing different variables.

3.3. ON–OFF Controller

The ON–OFF controller is represented in Figure 3 and operates by switching between two values, meaning that it involves an instantaneous change between two states [30].
In the context of this study and analysis, several variables play crucial roles in understanding and controlling the system shown in Figure 3. The Target (T) variable defines the desired location on the map, while the Actual Position (AP) variable is the precise position relative to a reference point. The On–Off Error (eON-OFF) variable represents the position error, where if it exceeds a certain threshold, a new trajectory is calculated. This error is the difference between the desired position (T) and the actual position (AP) of the system. The Angular Value (ωr) variable expresses the angular value associated with rotational or curvilinear movement. The Microcontroller (μC) is the “brain” of the system, responsible for processing the values obtained from the “cmd_vel” topic to control the UGV. The Voltage Right Wheel (VR) and Voltage Left Wheel (VL) variables indicate the voltages applied to the right and left wheels, respectively, of the locomotion system, influencing the movement and direction.
Based on the desired trajectory, two parallel trajectories were created with a tolerance distance of ±0.25 m. Initially, the robot aligns with the desired trajectory. If the robot’s position coincides with any point of these parallel trajectories during navigation, the algorithm performs a recalculation between the current position and the destination. This action is repeated until the robot’s position is within a 0.25 m radius (R) of the destination.
The algorithm is as follows (Algorithm 1):
Algorithm 1. ON–OFF controller algorithm.
Flag_Goal_Reached = FALSE
Flag_Rotation = TRUE
FOR coordinates in FILE:
   WHILE Flag_Goal_Reached = FALSE:
   IF detect_people = TRUE:
       V L = 0   a n d   V R = 0 (STOP MACHINE)
   ELSE:
       e O N O F F = ( T x A P x ) 2 + ( T y A P y ) 2
      IF e O N O F F R :
          V L = 0   a n d   V R = 0 (STOP MACHINE)
         Flag_Goal_Reached = TRUE

      IF Flag_Rotation = TRUE:
         IF Rotation_Finished:
             V L = 0   a n d   V R = 0 (STOP MACHINE)
            Flag_Rotation = FALSE
         ELSE:
             υ = 0   a n d   ω   0 (ROTATE MACHINE)
            IF 10_Seconds_Passed_Without_Changing_Position:
               INCREASE ROTATION ( ω + + )
      IF Flag_Rotation = FALSE:
         IF Not_Between_Lines:
            HeadingRotation = ActualHeading
            Flag_Rotation = TRUE
             V L = 0   a n d   V R = 0 (STOP MACHINE)
         ELSE:
            GO IN FRONT (constant Vr and Vl)
Algorithm 1 defines a navigation process and decision-making for the UGV’s movement. The system is designed to respond dynamically to environmental conditions and the proximity to the destination point. Algorithm 1 begins by setting two main flags: “Flag_Goal_Reached” and “Flag_Rotation”, initially configured as true or false, respectively. The algorithm processes the coordinates until “Flag_Goal_Reached” becomes true.
The first check in the algorithm is the detection of people; if detected, the UGV will stop moving to ensure safety. If no one is detected, the algorithm evaluates whether the destination has been reached. If the goal is reached, the machine stops, and “Flag_Goal_Reached” is set to true. If there is a rotation required (i.e., “Flag_Rotation” is true), the algorithm checks whether the rotation is complete. If the rotation is finished, the machine stops, and “Flag_Rotation” is set to false. If the rotation is not completed, the machine continues rotating, and after 10 s with no position change, the rotation speed is increased.
If rotation is not needed (i.e., “Flag_Rotation” is false), the algorithm checks whether the UGV is within the desired path. If it is not, “Flag_Rotation” is reactivated, the machine stops, and the UGV realigns its orientation. If the UGV is within the accepted limits, it continues moving towards the goal, as shown in Figure 4.

3.4. PID Controller

The PID (Proportional, Integral, and Derivative) controller is widely used in linear control systems, known for its ease of implementation and effectiveness in controlling processes and variables (such as temperature, pressure, speed) to a desired value [31]. PID control involves three separate control actions, whose outputs are summed to form a single output signal. The current reading of the controlled parameter is subtracted from the command to generate an error signal. This error signal is processed by three distinct units [32]. The PID controller is commonly used in industry and automated systems due to its effectiveness and ease of implementation, as shown in Figure 5 [33].
Proportional Action (P), also known as the proportional gain (Kp), multiplies the error between the desired value and the actual value by this coefficient. Therefore, the larger the error, the greater the correction applied by the controller. The proportional controller can correct the error, but if the gain is too high, it may cause oscillations around the desired value [34,35].
Integral Action (I) helps to eliminate the accumulated error over time. This control action, known as the integral gain (Ki), allows the controller to correct persistent errors, even if the proportional action is not sufficient to eliminate them. Additionally, the integral term is useful for eliminating steady-state error, which can occur when there is a constant disturbance in the system [36].
Derivative Action (D) predicts the rate of change of the error over time. This control action, known as the derivative gain (Kd), is useful to prevent excessive oscillations and reduces the controller’s response to rapid changes in the error variable. It acts as a “damping” effect that smooths the response and improves the overall stability of the system [37,38].
The combination of these terms allows the controller to react quickly to disturbances, correct persistent errors, and keep the controlled variable close to the desired value. The tuning of the coefficients is essential to optimize system performance, minimize oscillations, and improve the response time. The PID controller represents the contribution of these different control actions. Over 95% of control problems can be solved with this type of control system, although some may only require two control actions, such as PI (Proportional–Integral) without the derivative action or PD (Proportional–Derivative) without the integral action [39].

3.4.1. PID Heading Controller

The PID Heading Controller (PID-H) aims to control both linear and angular trajectories. To achieve this, two independent PID controllers are used, as shown in Figure 6, where the initial focus is located on a line with the destination coordinates. This initial alignment adjusts the UGV relative to the destination point with a precision of up to four degrees, which is the accepted angular threshold.
The error values related to the robot’s orientation and its position relative to the destination are updated during the navigation process. The system thus allows for a maximum limitation of ±2 degrees within the scope of orientation error. The voltage applied to the tracks is corrected when the controller detects that this limit has been exceeded. Therefore, the UGV stays on the path between the origin and the destination. As the angular error is reduced, this effect contributes to a smooth trajectory and applies a voltage level to the robot’s tracks corresponding to the calculated error. The angular error between the robot and the destination point is input as a reference into the PID controller as the robot starts its trajectory, intending to align the robot with the destination point as accurately as possible. The algorithm aims to optimize navigation, ensuring precise and smooth movement toward the destination.
In this study and analysis context, various variables play crucial roles in understanding and controlling the system shown in Figure 6.
The variable Desired Heading (θDes) represents the desired orientation or the angle to be reached or maintained by the system.
The variable Target (T) defines the desired location on the map. The variable Actual Position (AP) is the precise position relative to a reference point. The variable Heading Error (eHead) is the error between the desired angle (θDes) and the actual angle (θ) of the system. The variable Position Error (ePos) is the error between the desired position (T) and the actual position (AP) of the system. The variable Angular Value (ωr) represents the angular value associated with rotational or curvilinear movement. The variable Linear Value (Vr) represents the linear motion of the system, and the variable Actual Heading (θ) indicates the actual angle or current orientation of the system. The variable Microcontroller (μC) is the “brain” of the system, responsible for processing the values obtained from the “cmd_vel” topic to control the UGV. The variables Voltage Right Wheel (VR) and Voltage Left Wheel (VL) indicate the voltages applied to the right and left wheels, respectively, of the locomotion system to influence movement and direction.
The algorithm is shown in the pseudocode below (Algorithm 2), aiming to move as illustrated in Figure 7. It is somewhat more complex than the previous one, as it incorporates a PID controller in its control system.
Algorithm 2. PID Heading Controller algorithm.
Flag_Goal_Reached = FALSE
Flag_Rotation = TRUE
FOR coordinates in FILE:
   WHILE Flag_Goal_Reached = FALSE:
   IF detect_people = TRUE:
       V L = 0   a n d   V R = 0 (STOP MACHINE)

   ELSE:
      IF Flag_Rotation = TRUE
         IF Not_Aligned AND 10_Seconds_Passed_Without_Changing_Position:
             υ = 0   a n d   ω   0 (ROTATE MACHINE)
         ELSE:
            Original_Position = Actual_Position
            Flag_Rotation = FALSE

       e P o s i t i o n = ( T x A P x ) 2 + ( T y A P y ) 2

       θ D e s i r e d = a t a n 2 ( T y A P y   ,   T x A P x )

       e H e a d i n g = θ D e s i r e d θ R e a l

      IF  e P o s i t i o n R :
          V L = 0   a n d   V R = 0 (STOP MACHINE)
         Flag_Goal_Reached = TRUE
         Flag_Rotation = TRUE

      IF e H e a d i n g > Δ θ and e P o s i t i o n > R :
         Angular PID
          ω = K p θ e H e a d i n g + K i θ e H e a d i n g   d t + K d θ d e H e a d i n g d t
         Linear PID
          υ = K p l i n e a r e P o s i t i o n + K i l i n e a r e P o s i t i o n   d t + K d l i n e a r d e P o s i t i o n d t  

       V L = υ L 2 ω   AND   V R = υ + L 2 ω
The scenario outlined by the presented pseudocode defines a highly sensitive navigation process where the UGV dynamically adapts to various circumstances. The foundation of this process relies on two flags: “Flag_Goal_Reached” and “Flag_Rotation”. The first flag starts inactive, indicating that the destination has not yet been reached, while the second begins active, signaling the need for a rotation. The detection of people is a priority, leading to an immediate stop of the UGV if detected. In the absence of people, the algorithm guides the UGV according to the planned trajectory.
When a rotation is needed (“Flag_Rotation” is active), the algorithm checks whether it has been completed or if no position change has occurred after 10 s. If the rotation is completed, the machine stops, and “Flag_Rotation” is deactivated. However, if no position change occurs after 10 s, the “Flag_Rotation” is also deactivated. Otherwise, the machine is directed to perform the rotation.
When no further rotation is needed (“Flag_Rotation” is inactive), the algorithm checks whether the destination has been reached. If so, the machine stops, “Flag_Goal_Reached” is activated, and “Flag_Rotation” is reactivated to calculate the best orientation. If the destination is not reached, the algorithm calculates the distance and orientation errors relative to the destination. The linear and angular PID controllers ensure that the UGV maintains its precise trajectory, staying aligned with the destination point, as shown in Figure 7.

3.4.2. PID Heading Cross Track Error Controller

The PID CTE (Cross Track Error) controller autonomously manages both linear and angular trajectories using two separate PID controllers, as shown in Figure 8. The error values are continuously updated during the navigation process and include the robot’s relative position concerning the line and its final destination. A maximum tolerance of ±10 cm is considered for the position error relative to the desired trajectory. The controller adjusts the voltage supplied to both tracks when it detects that the robot is nearing the allowed tolerance. This adjustment enables the UGV to navigate accurately, keeping it close to the planned trajectory between the origin and destination.
The position error serves as a reference, allowing the system to modify the voltage applied to the tracks depending on the proximity to the destination. This means that the voltage can either increase or decrease based on the distance, enabling the UGV to adapt to changing conditions.
In this study and analysis, several variables play crucial roles in understanding and controlling the system shown in Figure 8. These are similar to the previously mentioned variables, except for the desired distance from the line (D_DFL), the current distance from the line (A_DFL), and the error in this distance (e_CTE).
The PID CTE algorithm, as shown in the pseudocode below (Algorithm 3), aims to move the UGV as depicted in Figure 9. This algorithm is quite similar to the previous one, but the error variable used as input for the PIDs is based on the distance between the robot and the desired trajectory.
Algorithm 3. PID Cross Track Error controller.
Flag_Goal_Reached = FALSE
Flag_Rotation = TRUE
FOR coordinates in FILE:
   WHILE Flag_Goal_Reached = FALSE:
   IF detect_people = TRUE:
       V L = 0   a n d   V R = 0 (STOP MACHINE)

   ELSE:
      IF Flag_Rotation = TRUE
         IF Not_Aligned AND 10_Seconds_Passed_Without_Changing_Position:
             υ = 0   a n d   ω   0 (ROTATE MACHINE)
         ELSE:
            Original_Position = Actual_Position
            Flag_Rotation = FALSE
      ELSE:
          e P o s i t i o n = ( T x A P x ) 2 + ( T y A P y ) 2

          e C T E = A c t u a l D i s t a n c e F r o m L i n e D e s i r e d D i s t a n c e F r o m L i n e

         IF  e P o s i t i o n R :
             V L = 0   a n d   V R = 0 (STOP MACHINE)
            Flag_Goal_Reached = TRUE
            Flag_Rotation = TRUE
         ELSE:
            Angular PID
             ω = K p D F L e C T E + K i D F L e C T E   d t + K d D F L d e C T E d t
            Linear PID
             υ = K p l i n e a r e P o s i t i o n + K i l i n e a r e P o s i t i o n   d t + K d l i n e a r d e P o s i t i o n d t

       V L = υ L 2 ω   AND   V R = υ + L 2 ω
This pseudocode outlines the UGV’s navigation approach, focusing on both efficiency and safety as it follows a predefined path. The flags “Flag_Goal_Reached” and “Flag_Rotation” are central to this algorithm, guiding the UGV’s behavior in response to various contexts. While traversing coordinates, the algorithm prioritizes two aspects: detecting people and adjusting the trajectory. If people are detected, the UGV immediately stops to ensure safety. In the absence of detection, the focus shifts to movement precision. When rotation is necessary (“Flag_Rotation” is activated), the system checks whether the UGV is misaligned and, if there is no positional change after 10 s (indicating it is stuck), the rotation is performed. If the criteria are not met, the original position is logged, and the “Flag_Rotation” is deactivated. When no further rotation is needed (“Flag_Rotation” = FALSE), the algorithm checks whether the destination has been reached. If the goal is met, the UGV stops, the “Flag_Goal_Reached” is activated, and the movement ceases. If the goal has not been reached, errors in distance from the target and line are calculated, allowing the UGV to adjust its trajectory accurately.

3.4.3. PID CTE + H

The PID CTE + H controller autonomously manages the UGV’s linear and angular trajectories using a set of two PID controllers, as depicted in Figure 10. This nonlinear controller consists of two distinct parts. Initially, the reference angle, θ, is obtained from the trajectory planning system, the “Path Planner”. In the block diagram, the external loop provides feedback by comparing the robot’s current trajectory with the planned trajectory provided by the “Path Planner”.
The obtained value is then converted into a correction angle through a proportional controller with a gain, Kct, resulting in a correction term, φ. This correction is subtracted from the θ value to obtain the new desired θ, which will be the new reference input for the internal loop of the block diagram. This internal loop, in turn, uses the current orientation with feedback to calculate the necessary actuation effect.
In this context, several variables play crucial roles in understanding and controlling the system depicted in Figure 10. The variable “Bearing of the path” (ϕ) represents the orientation the system should follow relative to a reference point.
The “Distance from point to line” (DDFPL) measures the perpendicular distance between a specific point and the reference line. This measure helps evaluate how close the system is to the desired route and correct any deviations. The “Cross track error” (e_CTE) measures the lateral deviation of the system from the desired trajectory. It indicates how far the system is from the planned route and is used to calculate corrections. The “Gain” (KCT) is a multiplicative factor applied to certain variables or controller actions. It regulates the intensity of corrections or system responses as needed. The “Corrective turn angle” (φ) determines the angle by which the system must adjust to correct deviations from the planned trajectory, guiding the system back onto the correct route.
The “Desired Heading” (θDes) represents the desired orientation or the angle the system should achieve or maintain. The “Target” (T) defines the desired location on the map. The “Actual Position” (AP) is the precise position relative to a reference point. The “Heading Error” (eHead) is the error between the desired angle (θDes) and the actual angle (θ) of the system. The “Position Error” (ePos) is the error between the desired position (T) and the actual position (AP) of the system.
The “Angular Value” (ωr) expresses the angular value associated with rotational or curvilinear motion. The “Linear Value” (Vr) represents the system’s linear motion, and the “Actual Heading” (θ) indicates the current orientation or real angle of the system. The “Microcontroller” (μC) is the system’s “brain”, responsible for processing the values obtained from the “cmd_vel” topic for UGV control. The “Voltage Right Wheel” (VR) and “Voltage Left Wheel” (VL) represent the voltages applied to the right and left wheels, respectively, of the locomotion system to influence movement and direction.
The CTE + H algorithm is shown in the pseudocode below (Algorithm 4) and is presented as depicted in Figure 11. It is a more complex algorithm than the previous ones because it includes both error variables from the earlier algorithms. This algorithm can be characterized as the integration of the PIDH and PIDCTE algorithms.
Algorithm 4. PID CTE + H controller.
IF No_Goals = TRUE
   RETURN FALSE
Flag_Goal_Reached = FALSE
Flag_Rotation = TRUE
WHILE Flag_Goal_Reached = FALSE:
   IF detect_people = TRUE:
       V L = 0   a n d   V R = 0 (STOP MACHINE)

   ELSE:
      IF Flag_Rotation = TRUE
         IF Not_Aligned AND 10_Seconds_Passed_Without_Changing_Position:
             υ = 0   a n d   ω   0 (ROTATE MACHINE)
         ELSE:
            Original_Position = Actual_Position
            Flag_Rotation = FALSE
      ELSE:
          e P o s i t i o n = ( T x A P x ) 2 + ( T y A P y ) 2

          e C T E = A c t u a l D i s t a n c e F r o m L i n e D e s i r e d D i s t a n c e F r o m L i n e

          ϕ = K C T e C T E

          θ D e s i r e d = θ p a t h ϕ  

          e H e a d i n g = θ D e s i r e d θ R e a l

         IF  e P o s i t i o n R :
             V L = 0   a n d   V R = 0 (STOP MACHINE)
            Flag_Goal_Reached = TRUE
            Flag_Rotation = TRUE

         ELSE:
            Angular PID
             ω = K p θ e H e a d i n g + K i θ e H e a d i n g   d t + K d θ d e H e a d i n g d t
            Linear PID
             υ = K p C T E e C T E + K i C T E e C T E   d t + K d C T E d e C T E d t  

       V L = υ L 2 ω   AND   V R = υ + L 2 ω
The pseudocode outlines a systematic approach for the UGV’s navigation, incorporating multiple factors to ensure effectiveness and safety. The process begins with a check for “No_Goals”, returning FALSE if no goal is set, thus preventing the execution of the algorithm. Following this, two flags, “Flag_Goal_Reached” and “Flag_Rotation”, are initialized, with the first set to FALSE, indicating that the goal has not yet been reached, and the second set to TRUE, signifying that rotation is required. At the core of the algorithm is a loop that continues until the goal is reached (“Flag_Goal_Reached” = FALSE).
During this loop, person detection takes priority, halting the UGV immediately if someone is detected. In scenarios where rotation is necessary (“Flag_Rotation” = TRUE), the algorithm evaluates the trajectory alignment and the elapsed time without any positional change. If trajectory adjustment is needed, the UGV is directed to rotate. Otherwise, the original position is updated, and the “Flag_Rotation” is deactivated.
When no further rotation is needed (“Flag_Rotation” = FALSE), the algorithm checks whether the goal has been achieved. If the goal is met, the machine stops, and “Flag_Goal_Reached” is activated. If the goal has not been reached, a series of error calculations are performed, involving the “Cross_Track_Error” (CTE) for orientation control, the position error for linear control, and the heading error for angular control.

3.4.4. PID Vector Field

The algorithm is shown in pseudocode below (Algorithm 5) and presented in Figure 12. It is somewhat different from the others, as it also uses PID control, but its error is derived from the vector sum of the virtual forces encountered during navigation.
Algorithm 5. PID Vector Field controller.
IF No_Goals = TRUE
   RETURN FALSE
Flag_Goal_Reached = FALSE
Flag_Rotation = TRUE
WHILE Flag_Goal_Reached = FALSE:
     IF detect_people = TRUE:
       V L = 0   a n d   V R = 0 (STOP MACHINE)
   ELSE:
      IF Flag_Rotation = TRUE
         IF Not_Aligned AND 10_Seconds_Passed_Without_Changing_Position:
             υ = 0   a n d   ω   0 (ROTATE MACHINE)
         ELSE:
            Original_Position = Actual_Position
            Flag_Rotation = FALSE
      ELSE:
            χ f = a t a n 2 ( w 2 y w 1 y   ,   w 2 x w 1 x )

            S * = z w 1 T w 2 w 1 w 2 w 1

            ε = | z S * w 2 w 1 + w 1 |

            ρ = s i g n ( w 2 w 1 z w 1 )

         IF  S * 1 :
             V L = 0   a n d   V R = 0 (STOP MACHINE)
            Flag_Goal_Reached = TRUE
            Flag_Rotation = TRUE

         IF  S * < 1 :
            ε = ρ ε

           IF  ε > τ :
                χ d = χ f ρ χ e

           IF  ε τ :
                χ d = χ f χ e ε τ k

         Angular PID
          ω = K p θ χ d + K i θ χ d   d t + K d θ d χ d d t
         Linear PID
          υ = K p l i n e a r S * + K i l i n e a r S *   d t + K d l i n e a r d S * d t  

       V L = υ L 2 ω   AND   V R = υ + L 2 ω
The pseudocode presents a dynamic strategy for the UGV’s navigation, incorporating multiple checks and calculations to ensure a precise and safe trajectory. The process begins with a check for “No_Goals”, which returns FALSE if no goals are defined, preventing the algorithm from proceeding without a clear purpose. Next, two flags are initialized: “Flag_Goal_Reached” and “Flag_Rotation”. The first starts as FALSE, indicating that the goal has not yet been reached, while the second is initialized as TRUE, signaling the need for rotation. The core of the algorithm is a loop that continues until the goal is reached (“Flag_Goal_Reached” = FALSE). During each iteration, a priority check for person detection is performed. If a positive detection occurs, the UGV is immediately halted, prioritizing safety. In cases where rotation is required (“Flag_Rotation” = TRUE), the algorithm evaluates whether the UGV is not aligned and whether 10 s have passed without positional change. If both criteria are met, the UGV is directed to rotate. Otherwise, the original position is updated, and the “Flag_Rotation” is deactivated. When rotation is no longer needed (“Flag_Rotation” = FALSE), the algorithm checks whether the goal has been reached. If the goal is met, the machine stops, and “Flag_Goal_Reached” is activated. If the goal has not been reached, the algorithm enters a series of calculations involving the “S_Star” error (for linear trajectory control) and the “Tau_Error” (for angular orientation control).
This algorithm is based on the concept of following a trajectory by creating a vector field around the path to be followed. The vectors in this field provide orientation commands to guide the robot towards the desired trajectory.
The goal is not to follow a moving point, but rather to position the robot along the trajectory as it moves. The vectors in this field are directed toward the path that should be followed, following the desired direction of navigation [40]. These vectors act as orientation commands for the robot. As shown in Figure 13, which represents a sample of a vector field between the start and the destination (black arrows), this approach directs the robot (red arrow) along the line between points from the start of its navigation.
The concept of vector fields, as shown in Figure 14, is comparable to that of potential fields, which have been widely used as a tool for trajectory planning. Potential fields can be applied in robot navigation for obstacle avoidance and collision prevention scenarios [41]. Vector fields differ from potential fields in that they do not always represent the gradient of a potential. Instead, the vector field simply indicates a desired direction of movement. As we can see, the vector field force (black arrow) will guide the robot between it starting point (green dot) and its goal (red dot).
The following steps represent the process of the Vector Field algorithm:
  • Calculation of the Orientation Angle ( χ f ): In this step, the desired orientation angle ( χ f ) is calculated for the robot to move from the first waypoint (w1) to the second waypoint (w2).
    χ f = a t a n 2 ( w 2 y w 1 y   ,   w 2 x w 1 x )
  • Calculation of Position Along the Trajectory (S*): Here, the robot’s position along the trajectory between the waypoints is determined. The vector connecting the current position (z) and the first waypoint (w1) is projected onto the vector between w1 and w2, giving a measure of where the robot is along the trajectory.
    S * = z w 1 T ( w 2 w 1 ) | w 2 w 1 |
  • Calculation of Distance to the Trajectory (ε): This step calculates the distance between the robot’s actual position (z) and the closest point on the trajectory between the waypoints. This helps understand how far the robot is from the desired path.
    ε = | z S * w 2 w 1 + w 1 |
  • Determination of the Side of the Trajectory (ρ): Here, a value (ρ) is calculated to indicate which side of the trajectory the robot is on. This is achieved using the cross product between the vector connecting the waypoints (w2 − w1) and the vector from the current position (z) to the first waypoint (w1). The sign of this value indicates whether the robot is to the left or right of the trajectory.
  • Verification of Position Relative to Waypoint 2: If the value of S* is greater than 1, it means the robot has passed the second waypoint. In this case, the robot transitions to the next waypoint, as it has reached the destination of the current waypoint.
  • Change of Waypoint: The transition to the next waypoint in the trajectory is made.
  • Continuation of the Process: If S * is less than 1, it means the robot is still between the waypoints, and its navigation continues.
  • Defining ε as ρε: In this step, the value of ε is updated to ρε, which represents the distance of the robot to the trajectory, considering which side of the path the robot is on.
  • Verification of Distance to the Trajectory: If the absolute value of ε is greater than a predefined threshold τ, it indicates that the robot is significantly far from the desired path.
  • Calculation of Desired Angle ( χ d ): If the robot is far from the trajectory, χ f is calculated as the difference between the reference angle χ f and the product of ρ and χ e , where χ e is a correction factor.
    χ d = χ f ρ χ e
  • Otherwise (Trajectory Distance Within the Limit): If the absolute value of ε is less than or equal to τ, it means the robot is close enough to the trajectory.
  • Calculation of Desired Angle with Correction ( χ d ): In this scenario, χ d is calculated as the difference between the reference angle χ f and the product of χ e , τ, and a factor k.
    χ d = χ f χ e ε τ k
  • End of the Process: The process concludes here.
These steps enable the robot to follow a desired trajectory using vector fields, adjusting its orientation and position dynamically to ensure that it stays on course while accounting for any deviations.

3.5. Process of Calculating PID Coefficients

To calculate the respective gains of the controller, there are several methods, which can be divided into two categories: closed-loop and open-loop methods. Numerous methods can be implemented for PID controller tuning, such as the Ziegler–Nichols (Z-N) method, Tyreus–Luyben (T_L), C-H-R, Cohen and Coon (C-C), Fertik, and Ciancone–Marlin (C-M) [42].
The Ziegler–Nichols (Z-N) and Cohen–Coon (C-C) controllers are simple and easy to implement. The Cohen–Coon method for PID control is an extension of the Ziegler–Nichols method. This technique improves the steady-state response, especially when there is a large delay in the process compared to the open-loop time constant [43]. To achieve this, the PID parameters are obtained through open-loop experiments, as shown in Figure 15.
From the obtained data, it is possible to calculate the associated gains, as shown in Table 3.

3.6. Evaluation Criteria for PID Control Algorithms

In the methodology for designing a PID controller, one of the most important performance criteria is the difference (error) between the system’s output and the reference value. Generally, optimization functions are formulated based on error equations, with the three most common being [45]:
  • Integral of the Absolute Error Magnitude (IAE);
  • Integral of the Squared Error (ISE);
  • Integral of the Time multiplied by the Absolute Error Magnitude (ITAE).
These are given as follows [45]:
I A E = 0 T e t d t
ISE = 0 T e t 2 d t
I T A E = 0 T t e t d t
To complement the values provided by the metrics given in formulas 6–8, multi-objective optimization (MOO) techniques were used with the selection of Pareto-optimal solutions. This method, as mentioned in [46], explains that optimization aims to maximize performance with minimal resources and is divided into exact methods, which guarantee optimal solutions but have limited applicability, and meta-heuristic methods, which effectively handle complex, real-world problems. In MOO, multiple conflicting objectives are addressed simultaneously, resulting in a set of Pareto-optimal solutions where no single solution is universally better, requiring trade-offs.
A decision vector x* ∈ S is Pareto-optimal if no other vector x ∈ S can improve all components without worsening at least one [47]. Mathematically, point x* ∈ S is Pareto-optimal only if there is no point x ∈ S such that f(x) ≤ f(x*) with at least one fi(x) > fi(x*) [46].
As noted by [48], all Pareto-optimal solutions in decision variable space form the Pareto-optimal set. Furthermore the representation of the Pareto optimal set in the objective function space is called the Pareto-optimal front [49], expressed as:
P F * = { f ( x * ) | x * P S * }
This indicates that the Pareto-optimal front (PF) is the set of objective function values for all Pareto-optimal solutions (PSs) in the decision space, showcasing the trade-offs between conflicting objectives.
In addition to the criteria mentioned, further evaluation metrics were added to complement the above criteria. These metrics consist of the mean, standard deviation, and maximum, with the scale being in meters. With these three metrics, the aim was to analyze the position error of the robot relative to the trajectory that the UGV should follow. Finally, the navigation time was also considered to determine which of the control algorithms could execute a given trajectory in the shortest possible time.

4. Experimental Results

The various control algorithms derived from the PID controller that were proposed were successfully analyzed and evaluated. It was possible to determine which control algorithms offer greater efficiency and precision. By placing the UGV on a forest terrain (i.e., unstructured) to investigate the differences between the presented controllers, real-time navigation data were collected during these practical experiments.
Thus, this section aims to present the experimental results regarding the process of tuning the PID coefficients (Kp, Ki, and Kd), followed by an analysis of the proposed control algorithms, highlighting the characteristics of each one.

4.1. Response of PID Parameters

For the PID gain calculations, the Cohen–Coon open-loop method was used. For each controller, two tests were conducted: one for the angular component and another for the linear component. In the linear component test, the UGV moved forward until reaching the requested reference of 8 m, where we observed the system’s response curve for each controller. In the angular component, the UGV was asked to change its reference orientation by 45°, and we also observed the response to this movement, as shown in Table 4.
After the values were calculated, it was possible to deduce and experiment with the values. The calculated values are represented in Table 5.

4.2. PID Algorithm’s Control Performance

To visualize the data from the experiments carried out for each control system, we created a visual presentation to provide a clear and comparative perspective of the performance of each controller. This practical approach aims to provide more practical and valuable insights into the behavior and effectiveness of navigation controllers in the real world. All the tests conducted can be observed in Figure 15.
After thoroughly analyzing the results obtained from the field tests, we decided to conduct additional tests to more precisely identify the most promising methods to be incorporated into an obstacle avoidance algorithm during navigation. Through this careful analysis, we aimed to select approaches that demonstrate consistency and effectiveness in a variety of situations. Figure 16 is a visual representation of the various paths taken under different control types.
We observed that the proposed destinations were successfully reached; however, since this was not an ideal environment and contained disturbances, additional comparisons were made by repeating the same trajectories for all algorithms. In our case, we considered the square movement, where the robot passed through the coordinates [(8.0, 0.0); (8.0, 8.0); (0.0, 8.0); (0.0, 0.0)], respectively. All tests started with the UGV facing east before navigation. In all tests, the robot used GPS + RTK technology, providing an accuracy of up to 2 cm. For all navigation tests, an offset of 0.2 m was considered until the destination was reached. For each of these tests, an analysis of the robot’s position error relative to the trajectory it should follow was performed. That is, the mean error, maximum error, and standard deviation were calculated for each situation. In the graphs, a position translation of 1.1 m is noticeable. This means that the robot’s location, instead of being at the “Sentry” point where the GPS is located, was now situated at the robot’s center of rotation, affecting the observed trajectories. This occurred because the position did not start from the origin point (0,0), but from the point (1,0).
To better clarify the different paths taken by the UGV, Figure 17 shows the impacts that the robot took and moved. This visualization enables an accurate analysis by presenting the observed data with the context given in Figure 16.
Table 6 presents the performance evaluation criteria used to evaluate and compare the proposed algorithms, focusing on their effectiveness in terms of error reduction, routing accuracy, and navigation efficiency.
The analysis of the data presented in the table reveals that the CTE (Cross Track Error) and Vector Field Control (VFC) algorithms outperform the others in terms of overall performance. In particular, the VFC algorithm exhibits the best results in key quantitative performance parameters, including ITAE (Integral Time Absolute Error), IAE (Integral Absolute Error), and ISE (Integral Square Error).
The VFC algorithm obtains the lowest values of ITAE (520.96), IAE (66.989), ISE (11.8488), indicating stability and accuracy with minimal accumulated errors over time. Moreover, the stationary error (Mean [m] = 0.18) and the mean (Standard Deviation [m]. = 0.17) show low values, indicating that a route is always closer to the correct route. During travel, the VFC is also efficient, completing the task in 82.46 s, which is the shortest among all algorithms considered.
Figure 18 illustrates the UGV navigating the 8 × 8 square path in the actual field where the PID controller algorithms were previously tuned. The figure comprises four distinct images, each capturing the robot positioned at one of the square’s corners.
These results indicate that the VFC algorithm performs particularly well for applications that require high accuracy in trajectory execution and time efficiency. The potential reason for this superior performance is the ability to continuously optimize control vectors, allowing the UGV (unmanned ground vehicle) to better adapt to planned changes in direction so that it meets and resolves sliding obstructions quickly and accurately. In contrast, the ON–OFF and other algorithms exhibit the highest cumulative error (ITAE = 2815.625, IAE = 118.19, and ISE = 46.844) and the largest position error (Max [m]). = 0.89). This indicates a very basic and inefficient method of control, meaning that they are highly unsuitable for applications requiring more optimized trajectories and higher accuracy.
To complement the validity of the robustness of the obtained values, the Pareto-optimal front can be observed in Figure 19, Figure 20 and Figure 21. These graphs demonstrate how improving one objective impacts others. In our case, the ideal focus is on minimizing each objective, highlighting that the Vector Field controller emerges as the optimal choice, dominating all other controllers.

5. Conclusions

In summary, the comprehensive research on the autonomous navigation of unmanned ground vehicles (UGVs) within unstructured environments, such as those commonly encountered in agriculture and forestry, has highlighted the vital importance of various PID control algorithms in enhancing their operational effectiveness. The capability of UGVs to navigate independently in these intricate environments is not merely a technological enhancement, but an essential requirement for efficiency, safety, and sustainability in tasks that are frequently hazardous or overly labor-intensive for human operators.
The study thoroughly assessed multiple PID control algorithms, including the ON–OFF controller, PID Heading controller, PID Cross Track Error (CTE) controller, PID CTE + Heading controller, and PID Vector Field controller. Each algorithm underwent rigorous testing in real-world scenarios using a forestry tractor converted into a UGV, equipped with advanced sensors for precise data acquisition. The evaluations revealed significant variations in performance metrics among the different control strategies.
Notably, the PID Vector Field controller was identified as the optimal approach, demonstrating exceptional performance regarding navigation efficiency, trajectory tracking precision, and adaptability to the unpredictable conditions inherent in unstructured terrain. Utilizing the multi-objective optimization framework confirmed that this method properly balanced stability, adaptability, and computing efficiency. This algorithm’s capacity to derive its error from the vector sum of virtual forces enabled dynamic adjustments during navigation, ensuring that the UGV could stay close to its intended path despite obstacles or irregular terrain features.
Additionally, the integration of high-accuracy GNSS-RTK positioning alongside inertial measurement units (IMUs) supplied the UGV with crucial data for the continuous real-time monitoring of its position and orientation. This confluence of technologies not only elevated the precision of the navigation system, but also fostered the formulation of reactive control strategies prioritizing safety and efficiency.
However, the performance of a PID control algorithm also depends on environmental factors. Variability in terrain conditions, such as soil, mud, or uneven surfaces, can affect the traction of the UGV, thereby complicating its navigation. Since the scope of this article focuses on unstructured environments, specifically forested areas, the presence of dense vegetation and trees may reduce the reliability of GNSS-RTK signals, potentially impacting the PID control algorithms.
The practical implications of these results are substantial. The effective adaptation of PID control algorithms for UGVs represents a significant advancement in robotics applications within sectors such as agriculture and forestry, where the demand for autonomous systems continues to grow. The capacity for UGVs to function effectively in challenging environments can reduce labor costs, lower environmental impacts, and enhance safety for human operators.
Furthermore, this research establishes a foundational framework for future progress in mobile robotics. By creating a performance evaluation framework based on criteria such as Integral of Absolute Error (IAE), Integral of Squared Error (ISE), and Integral of Time multiplied by Absolute Error (ITAE), along with metrics like mean, standard deviation, maximum position errors, and navigation time, the study allows for a thorough analysis of control algorithms. These metrics may serve as benchmarks for future research, facilitating the ongoing enhancement of UGV navigation technologies.

Author Contributions

Conceptualization, T.G., T.P. and H.M.; Methodology, T.G., T.P., F.D.G. and S.S.; Software, T.G., T.P., H.M. and F.D.G.; Validation, T.P., N.F., J.F., S.S. and A.V.; Formal analysis, F.D.G., N.F., J.F., S.S. and A.V.; Investigation, T.G., T.P., H.M. and F.D.G.; Resources, C.V. and N.F.; Writing—original draft, T.G., T.P. and N.F.; Writing—review & editing, C.V., N.F., J.F., S.S. and A.V.; Visualization, C.V.; Supervision, C.V., N.F., J.F., S.S. and A.V.; Project administration, N.F. and C.V.; Funding acquisition, N.F. and C.V. All authors have read and agreed to the published version of the manuscript.

Funding

The present work was funded in the scope of the following projects: E-Forest—Multi-agent Autonomous Electric Robotic Forest Management Framework, ref. POCI-01-0247-FEDER-047104 and by project F4F—Forest for Future, ref. CENTRO-08-5864-FSE-000031, co-financed by European Funds through the programs Compete 2020 and Portugal 2020. Also, this work was funded by the Portuguese Foundation for Science and Technology under the project grant UIDP/00760/2020 with the DOI 10.54499/UIDP/00760/2020|https://doi.org/10.54499/UIDP/00760/2020, project LA/P/0079/2020, DOI: 10.54499/LA/P/0079/2020|https://doi.org/10.54499/LA/P/0079/2020 and project grant UIDB/00760/2020 with the DOI 10.54499/UIDB/00760/2020|https://doi.org/10.54499/UIDB/00760/2020.

Data Availability Statement

Data is contained within the article.

Conflicts of Interest

The authors declare no conflicts of interest.

Abbreviations

The following abbreviations are used in this manuscript:
UGVsUnmanned Ground Vehicles
PIDProportional, Integral, and Derivative
RTK-GNSSReal-Time Kinematic Global Satellite Navigation System
GNSSGlobal Navigation Satellite System
INSInertial Navigation System
PID-HPID Heading Controller
PID-CTEPID Cross Track Error Controller
PID-CTE + HPID Cross Track Error + Heading Controller
PID-VFPID Vector Field
PIOProportional-Integral Observer
RCMARaised Cosine Moving Average
MIMOMultiple Inputs and Multiple Outputs
TTarget
APActual Position
eON-OFFOn–Off Error
ωrAngular Value
μCMicrocontroller
VRVoltage Right Wheel
VLVoltage Left Wheel
RRadius
PProportional Action
KpProportional Gain
IIntegral Action
KiIntegral Gain
DDerivative Action
KdDerivative Gain
PIProportional–Integral
PDProportional–Derivative
θDesDesired Heading
eHeadHeading Error
θDesDesired Angle
θActual Angle
ePosPosition Error
VrLinear Value
D_DFLDesired Distance from the Line
A_DFLCurrent Distance from the Line
e_CTEError in this Distance
ϕBearing of the Path
DDFPLDistance from Point to Line
ωrAngular Value
IAEIntegral of the Absolute Error Magnitude
ISEIntegral of the Squared Error
ITAEIntegral of the Time multiplied by the Absolute Error Magnitude
MOOMulti-Objective Optimization

References

  1. Fernandes, H.R.; Polania, E.C.M.; Garcia, A.P.; Barrero, O.; Albiero, D. Agricultural Unmanned Ground Vehicles: A Review from the Stability Point of View. Rev. Cienc. Agron. 2020, 51, e20207761. [Google Scholar] [CrossRef]
  2. Lytridis, C.; Kaburlasos, V.G.; Pachidis, T.; Manios, M.; Vrochidou, E.; Kalampokas, T.; Chatzistamatis, S. An Overview of Cooperative Robotics in Agriculture. Agronomy 2021, 11, 1818. [Google Scholar] [CrossRef]
  3. Oliveira, L.F.P.; Moreira, A.P.; Silva, M.F. Advances in Forest Robotics: A State-of-the-Art Survey. Robotics 2021, 10, 53. [Google Scholar] [CrossRef]
  4. Gameiro, T.; Pereira, T.; Viegas, C.; Di Giorgio, F.; Ferreira, N.F. Robots for Forest Maintenance. Forests 2024, 15, 381. [Google Scholar] [CrossRef]
  5. Wijayathunga, L.; Rassau, A.; Chai, D. Challenges and Solutions for Autonomous Ground Robot Scene Understanding and Navigation in Unstructured Outdoor Environments: A Review. Appl. Sci. 2023, 13, 9877. [Google Scholar] [CrossRef]
  6. Beycimen, S.; Ignatyev, D.; Zolotas, A. A Comprehensive Survey of Unmanned Ground Vehicle Terrain Traversability for Unstructured Environments and Sensor Technology Insights. Eng. Sci. Technol. Int. J. 2023, 47, 101457. [Google Scholar] [CrossRef]
  7. Ruslan, N.A.I.; Amer, N.H.; Hudha, K.; Kadir, Z.A.; Ishak, S.A.F.M.; Dardin, S.M.F.S. Modelling and Control Strategies in Path Tracking Control for Autonomous Tracked Vehicles: A Review of State of the Art and Challenges. J. Terramechanics 2023, 105, 67–79. [Google Scholar] [CrossRef]
  8. Huang, G.; Du, S.; Wang, D. GNSS Techniques for Real-Time Monitoring of Landslides: A Review. Satell. Navig. 2023, 4, 5. [Google Scholar] [CrossRef]
  9. Jing, Y.; Li, Q.; Ye, W.; Liu, G. Development of a GNSS/INS-Based Automatic Navigation Land Levelling System. Comput. Electron. Agric. 2023, 213, 108187. [Google Scholar] [CrossRef]
  10. Yan, W.; Bastos, L.; Magalhaes, A. Performance Assessment of the Android Smartphone’s IMU in a GNSS/INS Coupled Navigation Model. IEEE Access 2019, 7, 171073–171083. [Google Scholar] [CrossRef]
  11. Song, J.; Li, W.; Duan, C.; Zhu, X. R2-GVIO: A Robust, Real-Time GNSS-Visual-Inertial State Estimator in Urban Challenging Environments. IEEE Internet Things J. 2024, 11, 22269–22282. [Google Scholar] [CrossRef]
  12. Bai, X.; Hsu, L.-T. GNSS/Visual/IMU/Map Integration Via Sliding Window Factor Graph Optimization for Vehicular Positioning in Urban Areas. IEEE Trans. Intell. Veh. 2024; 1–11, Early Access. [Google Scholar] [CrossRef]
  13. Rouzegar, H.; Ghanbarisabagh, M. A Novel on–off Linear Quadratic Regulator Control Approach for Satellite Rendezvous. Aerosp. Syst. 2023, 6, 613–620. [Google Scholar] [CrossRef]
  14. Khan, H.; Khatoon, S.; Gaur, P.; Abbas, M.; Saleel, C.A.; Khan, S.A. Speed Control of Wheeled Mobile Robot by Nature-Inspired Social Spider Algorithm-Based PID Controller. Processes 2023, 11, 1202. [Google Scholar] [CrossRef]
  15. Bello, A.; Olfe, K.S.; Rodríguez, J.; Ezquerro, J.M.; Lapuerta, V. Experimental Verification and Comparison of Fuzzy and PID Controllers for Attitude Control of Nanosatellites. Adv. Space Res. 2023, 71, 3613–3630. [Google Scholar] [CrossRef]
  16. Efheij, H.; Albagul, A.; Ammar Albraiki, N. Comparison of Model Predictive Control and PID Controller in Real Time Process Control System. In Proceedings of the 2019 19th International Conference on Sciences and Techniques of Automatic Control and Computer Engineering (STA), Sousse, Tunisia, 24–26 March 2019; IEEE: Piscataway, NJ, USA, 2019; pp. 64–69. [Google Scholar]
  17. Ji, Y.; Wu, X.; Shang, Y.; Fu, H.; Yang, J.; Wu, W. Unmanned Ground Vehicle in Unstructured Environments Applying Improved A-Star Algorithm. In Proceedings of the 2024 4th International Conference on Computer, Control and Robotics (ICCCR), Shanghai, China, 19–21 April 2024; IEEE: Piscataway, NJ, USA, 2024; pp. 166–170. [Google Scholar]
  18. Zhang, L.; Jiang, Y.; Chen, G.; Tang, Y.; Lu, S.; Gao, X. Heading Control of Variable Configuration Unmanned Ground Vehicle Using PID-Type Sliding Mode Control and Steering Control Based on Particle Swarm Optimization. Nonlinear Dyn. 2023, 111, 3361–3378. [Google Scholar] [CrossRef]
  19. Sun, Y.-P.; Liang, Y.-C. Vector Field Path-Following Control for a Small Unmanned Ground Vehicle with Kalman Filter Estimation. Proc. Inst. Mech. Eng. Part B J. Eng. Manuf. 2022, 236, 1885–1899. [Google Scholar] [CrossRef]
  20. Parque, V.; Khalifa, A. PID Tuning Using Differential Evolution With Success-Based Particle Adaptations. IEEE Access 2023, 11, 136219–136268. [Google Scholar] [CrossRef]
  21. Vijayakumar, M.; Sakthivel, R.; Mohammadzadeh, A.; Karthick, S.A.; Marshal Anthoni, S. Proportional Integral Observer Based Tracking Control Design for Markov Jump Systems. Appl. Math. Comput. 2021, 410, 126467. [Google Scholar] [CrossRef]
  22. Song, W.; Jin, A. Observer-Based Model Reference Tracking Control of the Markov Jump System with Partly Unknown Transition Rates. Appl. Sci. 2023, 13, 914. [Google Scholar] [CrossRef]
  23. Gomathi, N.; Rajathi, K. Adaptive Path Planning for Unknown Environment Monitoring. J. Ambient. Intell. Smart Environ. 2023, 15, 287–314. [Google Scholar] [CrossRef]
  24. Farag, W.; Saleh, Z. Tuning of PID Track Followers for Autonomous Driving. In Proceedings of the 2018 International Conference on Innovation and Intelligence for Informatics, Computing, and Technologies (3ICT), Sakhier, Bahrain, 18–20 November 2018; IEEE: Piscataway, NJ, USA, 2018; pp. 1–7. [Google Scholar]
  25. Zangina, U.; Buyamin, S.; Abidin, M.S.Z.; Mahmud, M.S.A.; Hasan, H.S. Non-Linear PID Controller for Trajectory Tracking of a Differential Drive Mobile Robot. J. Mech. Eng. Res. Dev. 2020, 43, 255–270. [Google Scholar]
  26. Akopov, A.S.; Beklaryan, L.A.; Beklaryan, A.L. Simulation-Based Optimisation for Autonomous Transportation Systems Using a Parallel Real-Coded Genetic Algorithm with Scalable Nonuniform Mutation. Cybern. Inf. Technol. 2021, 21, 127–144. [Google Scholar] [CrossRef]
  27. Duro Inertial User Manual [UM-110008-02]. Available online: https://www.swiftnav.com/resource-files/Duro%20Inertial/v2/Manual/Duro%20Inertial%20User%20Manual%20[UM-110008-02].pdf (accessed on 20 January 2025).
  28. Pereira, T.; Gameiro, T.; Viegas, C.; Santos, V.; Ferreira, N. Sensor Integration in a Forestry Machine. Sensors 2023, 23, 9853. [Google Scholar] [CrossRef] [PubMed]
  29. Pereira, T.; Santos, V.; Gameiro, T.; Viegas, C.; Ferreira, N. Evaluation of Different Filtering Methods Devoted to Magnetometer Data Denoising. Electronics 2024, 13, 2006. [Google Scholar] [CrossRef]
  30. Edamana, B.; Oldham, K. An Optimal On-off Controller with Switching Costs Using Non-Linear Binary Programming. In Proceedings of the 2009 American Control Conference, St. Louis, MO, USA, 10–12 June 2009; IEEE: Piscataway, NJ, USA, 2009; pp. 4227–4232. [Google Scholar]
  31. Borase, R.P.; Maghade, D.K.; Sondkar, S.Y.; Pawar, S.N. A Review of PID Control, Tuning Methods and Applications. Int. J. Dynam. Control 2021, 9, 818–827. [Google Scholar] [CrossRef]
  32. Holland, J.M. Designing Mobile Autonomous Robots; Elsevier Newnes: Amsterdam, The Netherlands; Boston, MA, USA, 2004; ISBN 978-0-7506-7683-0. [Google Scholar]
  33. Åström, K.J.; Murray, R.M. Feedback Systems: An Introduction for Scientists and Engineers; Princeton University Press: Princeton, NJ, USA, 2008; ISBN 9780691135762. [Google Scholar]
  34. Raj, R.; Kos, A. A Comprehensive Study of Mobile Robot: History, Developments, Applications, and Future Research Perspectives. Appl. Sci. 2022, 12, 6951. [Google Scholar] [CrossRef]
  35. Rubio, F.; Valero, F.; Llopis-Albert, C. A Review of Mobile Robots: Concepts, Methods, Theoretical Framework, and Applications. Int. J. Adv. Robot. Syst. 2019, 16, 1729881419839596. [Google Scholar] [CrossRef]
  36. Sathiabalan, N.A.; Lokimi, A.F.M.; Jin, O.Z.; Hasrin, N.S.M.; Zain, A.S.M.; Ramli, N.; Zakaria, H.L.; Ariffin, W.N.S.F.W.; Hashim, N.B.M.; Taib, M.H.M. Autonomous Robotic Fire Detection and Extinguishing System. J. Phys. Conf. Ser. 2021, 2107, 012060. [Google Scholar] [CrossRef]
  37. Herath, D.; St-Onge, D. (Eds.) Foundations of Robotics: A Multidisciplinary Approach with Python and ROS; Springer Nature: Singapore, 2022; ISBN 978-981-19198-2-4. [Google Scholar]
  38. Amer, N.H.; Zamzuri, H.; Hudha, K.; Kadir, Z.A. Modelling and Control Strategies in Path Tracking Control for Autonomous Ground Vehicles: A Review of State of the Art and Challenges. J. Intell. Robot. Syst. 2017, 86, 225–254. [Google Scholar] [CrossRef]
  39. Chemical Process Dynamics and Controls. Available online: https://open.umich.edu/sites/default/files/downloads/chemical_process_dynamics_and_controls-book_1.pdf (accessed on 20 January 2025).
  40. Nelson, D.R.; Barber, D.B.; McLain, T.W.; Beard, R.W. Vector Field Path Following for Small Unmanned Air Vehicles. In Proceedings of the 2006 American Control Conference, Minneapolis, MN, USA, 14–16 June 2006; IEEE: Piscataway, NJ, USA, 2006; p. 7. [Google Scholar]
  41. Borenstein, J.; Koren, Y. The Vector Field Histogram-Fast Obstacle Avoidance for Mobile Robots. IEEE Trans. Robot. Automat. 1991, 7, 278–288. [Google Scholar] [CrossRef]
  42. Berner, J.; Soltesz, K.; Hägglund, T.; Åström, K.J. An Experimental Comparison of PID Autotuners. Control Eng. Pract. 2018, 73, 124–133. [Google Scholar] [CrossRef]
  43. Sen, R.; Pati, C.; Dutta, S.; Sen, R. Comparison Between Three Tuning Methods of PID Control for High Precision Positioning Stage. Mapan 2015, 30, 65–70. [Google Scholar] [CrossRef]
  44. Isdaryani, F.; Feriyonika, F.; Ferdiansyah, R. Comparison of Ziegler-Nichols and Cohen Coon Tuning Method for Magnetic Levitation Control System. J. Phys. Conf. Ser. 2020, 1450, 012033. [Google Scholar] [CrossRef]
  45. Almabrok, A.; Psarakis, M.; Dounis, A. Fast Tuning of the PID Controller in An HVAC System Using the Big Bang–Big Crunch Algorithm and FPGA Technology. Algorithms 2018, 11, 146. [Google Scholar] [CrossRef]
  46. Sharma, S.; Kumar, V. A Comprehensive Review on Multi-Objective Optimization Techniques: Past, Present and Future. Arch. Computat. Methods Eng. 2022, 29, 5605–5633. [Google Scholar] [CrossRef]
  47. Goos, G.; Hartmanis, J.; van Leeuwen, J.; Hutchison, D.; Kanade, T.; Kittler, J.; Kleinberg, J.M.; Kobsa, A.; Mattern, F.; Mitchell, J.C.; et al. Lecture Notes in Computer Science; Springer: Berlin/Heidelberg, Germany, 1973. [Google Scholar]
  48. Deb, K. Multi-Objective Optimization Using Evolutionary Algorithms: An Introduction. In Multi-Objective Evolutionary Optimisation for Product Design and Manufacturing; Springer: London, UK, 2011; pp. 3–34. [Google Scholar]
  49. Cui, Y.; Geng, Z.; Zhu, Q.; Han, Y. Review: Multi-Objective Optimization Methods and Application in Energy Saving. Energy 2017, 125, 681–704. [Google Scholar] [CrossRef]
Figure 1. Robotic platform (forest tractor) equipped with a sensory box: (a) UGV; (b) sensory box (Sentry) to control the UGV.
Figure 1. Robotic platform (forest tractor) equipped with a sensory box: (a) UGV; (b) sensory box (Sentry) to control the UGV.
Algorithms 18 00063 g001
Figure 2. Process of acquiring the variables to be implemented in the algorithms of the PID control.
Figure 2. Process of acquiring the variables to be implemented in the algorithms of the PID control.
Algorithms 18 00063 g002
Figure 3. ON–OFF controller block diagram.
Figure 3. ON–OFF controller block diagram.
Algorithms 18 00063 g003
Figure 4. Trajectory with the ON–OFF algorithm.
Figure 4. Trajectory with the ON–OFF algorithm.
Algorithms 18 00063 g004
Figure 5. Basic description of the PID controller.
Figure 5. Basic description of the PID controller.
Algorithms 18 00063 g005
Figure 6. Controller with error associated with heading.
Figure 6. Controller with error associated with heading.
Algorithms 18 00063 g006
Figure 7. Trajectory with the PID Heading algorithm.
Figure 7. Trajectory with the PID Heading algorithm.
Algorithms 18 00063 g007
Figure 8. Controller with error associated with trajectory distance.
Figure 8. Controller with error associated with trajectory distance.
Algorithms 18 00063 g008
Figure 9. Trajectory with the PID CTE algorithm.
Figure 9. Trajectory with the PID CTE algorithm.
Algorithms 18 00063 g009
Figure 10. CTE + H controller.
Figure 10. CTE + H controller.
Algorithms 18 00063 g010
Figure 11. Trajectory with the CTE + H algorithm.
Figure 11. Trajectory with the CTE + H algorithm.
Algorithms 18 00063 g011
Figure 12. Trajectory with the Vector Field algorithm.
Figure 12. Trajectory with the Vector Field algorithm.
Algorithms 18 00063 g012
Figure 13. Typical magnetic field in navigation with the Vector Field algorithm.
Figure 13. Typical magnetic field in navigation with the Vector Field algorithm.
Algorithms 18 00063 g013
Figure 14. Representation of the variables in the Vector Field algorithm.
Figure 14. Representation of the variables in the Vector Field algorithm.
Algorithms 18 00063 g014
Figure 15. Open-loop reaction curve [44].
Figure 15. Open-loop reaction curve [44].
Algorithms 18 00063 g015
Figure 16. Tests conducted in a real environment.
Figure 16. Tests conducted in a real environment.
Algorithms 18 00063 g016
Figure 17. Final result of the trajectory of each PID control algorithm (separately).
Figure 17. Final result of the trajectory of each PID control algorithm (separately).
Algorithms 18 00063 g017
Figure 18. Representation of all paths taken on the terrain during the execution of the 8 × 8 m squares: (a) initial position; (b) first coordinate; (c) second coordinate; (d) third coordinate.
Figure 18. Representation of all paths taken on the terrain during the execution of the 8 × 8 m squares: (a) initial position; (b) first coordinate; (c) second coordinate; (d) third coordinate.
Algorithms 18 00063 g018aAlgorithms 18 00063 g018b
Figure 19. Pareto front between ITAE and IAE objectives.
Figure 19. Pareto front between ITAE and IAE objectives.
Algorithms 18 00063 g019
Figure 20. Pareto front between ITAE and ISE objectives.
Figure 20. Pareto front between ITAE and ISE objectives.
Algorithms 18 00063 g020
Figure 21. Pareto front between IAE and ISE objectives.
Figure 21. Pareto front between IAE and ISE objectives.
Algorithms 18 00063 g021
Table 1. Advantages and Disadvantages of each type of controller.
Table 1. Advantages and Disadvantages of each type of controller.
ON–OFFPIDFuzzy LogicPredictive Control
Simplicity××
Accuracy×
Computational Cost××
Stability×
Speed
Tuning×
Table 2. Behavioral responses based on “cmd_vel” values.
Table 2. Behavioral responses based on “cmd_vel” values.
Linear Velocity (v)Angular Velocity (w)Behavior
v = 1w = 0Front Linear Movement
v = −1w = 0Back Linear Movement
v = 0w = 1Rotate Anti-Clockwise
v = 0w = −1Rotate Clockwise
v = 0.5w = 0.5Circular Movement Anti-Clockwise
v = 0.5w = −0.5Circular Movement Clockwise
Table 3. Gain calculation formulas [43].
Table 3. Gain calculation formulas [43].
Cohen–CoonKCTITD τ a
PID 1.35 a 1 + 0.18 τ 1 τ 2.5 2.0 τ 1 0.39 τ L 0.37 0.37 τ 1 0.81 τ L L L + T K p r o c e s s L T
Table 4. Graphs of the responses obtained for each PID control algorithm.
Table 4. Graphs of the responses obtained for each PID control algorithm.
Linear ResponseAngular Response
PID-HAlgorithms 18 00063 i001Algorithms 18 00063 i002
PID-CTEAlgorithms 18 00063 i003Algorithms 18 00063 i004
PID + CTE + HAlgorithms 18 00063 i005Algorithms 18 00063 i006
PID VFUses S*Algorithms 18 00063 i007
Table 5. Parameters obtained for each PID control algorithm.
Table 5. Parameters obtained for each PID control algorithm.
ControllerPID Linear CoefficientPID Angular Coefficient
KpKiKdKpKiKd
PID H0.6420.0710.900.1010.00540.0040
PID CTE1.8820.6070.830.0840.02950.0376
PID CTE + H0.2980.0210.690.2970.4110.0546
PIDH (VF)Uses S*0.3850.10260.0211
Table 6. Evaluation criteria applied to each controller during the experiments.
Table 6. Evaluation criteria applied to each controller during the experiments.
AlgorithmITAEIAEISEMean [m]Standard Deviation [m]Max [m]Navigation Time [s]
ON–OFF2815.625118.1946.8440.330.190.89103.60
Heading1695.307138.1144.18360.210.180.8588.90
CTE1541.619131.1346.90710.180.140.6586.45
CTE + H1257.30595.30319.67730.210.190.7493.60
Vector Field520.962966.98911.84880.180.170.6682.46
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Gameiro, T.; Pereira, T.; Moghadaspoura, H.; Di Giorgio, F.; Viegas, C.; Ferreira, N.; Ferreira, J.; Soares, S.; Valente, A. Evaluation of PID-Based Algorithms for UGVs. Algorithms 2025, 18, 63. https://doi.org/10.3390/a18020063

AMA Style

Gameiro T, Pereira T, Moghadaspoura H, Di Giorgio F, Viegas C, Ferreira N, Ferreira J, Soares S, Valente A. Evaluation of PID-Based Algorithms for UGVs. Algorithms. 2025; 18(2):63. https://doi.org/10.3390/a18020063

Chicago/Turabian Style

Gameiro, Tiago, Tiago Pereira, Hamid Moghadaspoura, Francesco Di Giorgio, Carlos Viegas, Nuno Ferreira, João Ferreira, Salviano Soares, and António Valente. 2025. "Evaluation of PID-Based Algorithms for UGVs" Algorithms 18, no. 2: 63. https://doi.org/10.3390/a18020063

APA Style

Gameiro, T., Pereira, T., Moghadaspoura, H., Di Giorgio, F., Viegas, C., Ferreira, N., Ferreira, J., Soares, S., & Valente, A. (2025). Evaluation of PID-Based Algorithms for UGVs. Algorithms, 18(2), 63. https://doi.org/10.3390/a18020063

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop