Published at : 18 Sep 2024
Volume : IJtech
Vol 15, No 5 (2024)
DOI : https://doi.org/10.14716/ijtech.v15i5.6527
Vo Thu Ha | Control and automation engineering technology, Faculty of Electrical-Automation Engineering, University of Economics - Technology for Industries (UNETI), Hanoi, Vietnam |
Than Thi Thuong | Control and automation engineering technology, Faculty of Electrical-Automation Engineering, University of Economics - Technology for Industries (UNETI), Hanoi, Vietnam |
Nguyen Thi Thanh | Control and automation engineering technology, Faculty of Electrical-Automation Engineering, University of Economics - Technology for Industries (UNETI), Hanoi, Vietnam |
This article presents an Adaptive Fuzzy Logic
Dynamic Surface Controller (AFDSC) combined with the A* optimal path-finding
algorithm for mobile robots' following trajectory tracking with the nonlinear
system changes in robot parameters and is affected by wheel sliding friction
disturbances when operating on different terrains. This algorithm is built
based on the DSC dynamic sliding surface control algorithm, promoting the
effective advantages of DSC and using fuzzy logic to adaptively adjust the
coefficients of the virtual control signal and keep The system status signal
located on the sliding surface to overcome the instability of DSC when encountering
this state. The stability and convergence of the closed-loop system are
guaranteed based on Lyapunov analysis. The robot's path planning trajectory is
performed by the A* algorithm. At the same time, the content of the article
mentions programming and experimental operation for mobile robots using the
ROS2 Rolling with Focal (20.04) software operating system on the Jetson Nano 4G
embedded computer. The correctness, the proposed controller’s effectiveness,
and the possibility of practical applications. Orbits are set as two periodic
functions of period T as follows. Theoretical and experimental simulation
results with position deviation-axis from 0.0038(m) to 0.0063(m), y-axis from
0.0029(m) to 0.0049(m), from 0.0021(rad)
to 0.0035(rad). And experimental results with position error in the x-axis from
0.0062(m) to 0.0105(m), y-axis from 0.0042(m) to 0.0069(m), and 0.0031(rad) to 0.0053(rad)).
Adaptive controller; Adaptive Fuzzy Dynamic Surface Controlzy (AFDSC); Dynamic Surface Control (DSC); Mobile Robot; Robot operating system (ROS)
Nowadays, mobile
robots have been integrated into various modern intelligent systems, including
production systems, logistics, hospitals, smart factories and warehouses. For
example, there are unmanned logistics transportation systems that incorporate
receiving devices and automatic delivery. The problem of motion control for
wheel-type mobile robots has attracted the attention of scientists around the
world. Mobile robots are among the
systems subject to nonholonomic constraints (Rusdinar
et al., 2021; Xin et al., 2016). Furthermore, it is a
nonlinear many-input-many-out system (Li, Wang, and
Zhu, 2010).
Advancements in control theory have introduced various methods for designing control laws for mobile robots, including sliding control, (Park et al., 2009; Chwa, 2004) sustainable control (Jiang, 2000), adaptive control (Ye and Wang, 2020; Rubio, Valero, and Llopis-Albert, 2019; Nguyen et al., 2018), backstepping control (Liu et al., 2021; Feng and Wang, 2021), output feedback linearization (Aldo et al., 2021; Rabbani and Memon, 2021). These control laws were designed with the assumption that "the wheel only rolls without slipping." However, in practical applications, the condition that the wheels only roll without slipping can often be violated. That is, wheel slippage has occurred (Zhang et al., 2022; Liu, et al., 2021).
Wheel slippage can occur due to factors like low
friction on the floor or centrifugal forces during curved motion. Therefore, in
such situations, if control performance is to be improved, it is necessary to design
a controller capable of compensating for wheel slippage. The problem of wheel
slip compensation control for mobile robots has had many scientists worldwide
spend time researching and solving this problem. However, the majority of
studies are carried out under the assumption that the slip angle (Hoang and Kang, 2016; Lenain et al., 2010; Low and
Wang, 2008) and the friction coefficient between the wheel and the road
surface (Elsayed et al., 2019; Chen et
al., 2018) are always accurately measured through sensors.
Quantities, including translational acceleration, angular acceleration,
translational velocity, and angular velocity, can all be easily measured
directly through sensors, but the sliding angle and friction coefficient are
very small. difficult to measure (Bayar et al.,
2016). To measure these signals accurately and reliably, the system must
be integrated with complex and expensive sensors (Bayar
et al., 2016).
Several control methods have been proposed to
address wheel slippage without requiring precise parameter measurements.
Instead, the negative effect of wheel slippage on trajectory tracking
performance will be compensated indirectly by the controllers. The control law
in (Zhang et al., 2020) is designed
in the global coordinate system OXY, so it requires measuring velocities in
this global system. This velocity measurement task was solved using the
supper-twisting observer. The estimation results from this observer may contain
errors accumulated during robot operation. So the ability to implement the
control method in (Zhang et al., 2020)
is still limited. To overcome this drawback, the adaptive sustainable tracking
control method is based on the backstepping technique (Xu,
Yang, and Gadsden, 2020); creating
a reverse impact from kinematics into dynamics) based on a Gaussian wave
network for mobile robots to compensate for wheel slippage, model uncertainty,
and external noise, show smaller position tracking errors compared to the
control method (Zhang et al., 2020) ,
which has asymptotically converged to zero. However, the disadvantage of this
method is that it requires a very large input control signal (torque) at the
initial time, the amount of calculation is large and complex, and it takes a
lot of time to calculate due to having to calculate the derivative in each
iteration step.
Sliding
mode controller (SMC) has also been used (Attia and
Suan, 2024; Edalati et al., 2018) due to its superior properties
when compared to Backstepping, particularly when the system is exposed to
noise. Sliding control is preferred for its robustness, rapid response,
straightforward control rules, and ease of implementation. Sliding controllers
can be used for a wide class of nonlinear systems with uncertain parameters and
interference effects. However, the limitation of the SMC algorithm is the
chattering phenomenon, and reducing this phenomenon requires the object model
to be accurate. This goes against the properties of the robot model, which is
parameter uncertainty. To improve control quality in (Gore
et al., 2015), the structure and method of building a dynamic
sliding surface controller (DSC) were presented. In particular, when the system
contains uncertain components, research focuses on improving and developing the
multi-sliding surface controller (MSSC). The design method also determines the
control signal based on the Lyapunov control function, so DSC ensures a stable
closed system and can adapt to the uncertain composition of the system and
deviations within certain limits. The design steps are similar to the
Backstepping set design steps; however, to avoid having to take derivatives in
the iteration steps for the virtual control signal, DSC has added a low-pass
filter, both to get information about medium derivative to filter out
high-frequency internal noises appearing in the control object (Qi et al., 2018). To improve control
quality, an adaptive controller based on the dynamic sliding surface control
(DSC) technique combined with a fuzzy logic system (Wang,
Wang, and Han, 2021) is studied because the fuzzy adaptive controller
has a simple adjustment mechanism in design and installation (Rahman, Hassan, and Ihsan, 2022). This has opened
up a new possible research direction for wheeled mobile robots (WMR) with
horizontal sliding components; then integrating embedded programming on the
Jetson embedded computer platform and the robot operating system (ROS); the
STM32 microcontroller creates test autonomous vehicle system with the A*
pathfinding algorithm. For fixed environments (warehouses, farms, factories,
etc.), path planning algorithms such as Dijkstra, A*, and D* are commonly used.
Because these algorithms have the advantage of finding the fastest path in a
static environment, the computational methods of these algorithms are also
quite fast (Liu et al., 2023; Alshammrei Boubaker, and Kolsi, 2022; Hou et al.,
2022).
In
this article, the authors propose to use A*, D*, or Dijkstra search algorithms
to plan the path for autonomous robots in a static environment with fixed obstacles.
In the article (Chen et al., 2009),
the authors also analyze the expansion and development algorithms of the A*
algorithm to see the optimal usability of the algorithm in planning the path
for the robot when we use it using the A* algorithm. In this paper, the authors
will choose algorithm A* to plan the fastest path for an omnidirectional mobile
robot in a static environment. This article proposes a new control structure
with a kinematic and dynamic model of a mobile robot when sliding sideways using
only one control loop, and designs a trajectory tracking controller for
self-propelled vehicles based on the algorithm. Dynamic sliding surface control
and adaptive control structure based on a fuzzy logic system (AFDSC) with an A*
path-finding algorithm to ensure a stable closed system.
There
are five main sections on this page. Target research and kinetic and dynamic
models are introduced in Sections 1 and 2. Presenting the suggested controller
is Section 3. The simulation results of the suggested controller are included
in Part 4. The conclusion is the concluding section.
Kinetic Model of An Autonomous Vehicle
2.1. Kinetics of autonomous robots
Consider
a self-propelled robot as depicted in Figure 1. Where: is the radius of the
active wheel; A is the midway of two
active wheels; C is the robot's
center of gravity's coordinates;
The
position of the robot is determined by the identity vector are the point
coordinates C).
The state
vector can be represented by the following five generic coordinates (1):
With:
Figure 1 Kinetic
relationship of self-propelled robot
According to the reference
(Nardênio and Douglas, 2021; Mohareri, 2009) we
have the kinematic equation of the robot, which will be written as equation (2)
as follows:
Where
Provide
sufficient detail methods to allow the work to be reproduced. Methods already
published should be indicated by a reference: only relevant modifications
should be described.
2.2. Dynamics of autonomous robots
The dynamic equation of a
mobile robot can be characterized as follows, according to documents (Nardênio
and Douglas, 2021; Chen et al., 2009)(3).
where (3): M(q)
where: m
From
equation (2), we can prove that the transformation matrix H(q)
We differentiate
the equation (2) we have (5):
From there, we
have the system's dynamic equation as follows (6):
3. Development of an A* pathfinding algorithm and
an adaptive Sliding-fuzzy controller for mobile robots
3.1.
Design in sliding
mode
According to documentation
[3], the recommended state variables are as follows:
Combining
the kinematics equation (2) and equation (7), we get:
From
equations (6), (7), and (8), we get the state model (9):
First,
the set
Assume
that the control signal is virtual in the design of the DSC controller. is the
input to the first-order low-pass filter with the expression (11):
with is the appropriate diagonal constant matrix value whose elements are positive values.
After
calculating the virtual control law,
With
To
demonstrate the availability of virtual control signals, choose the first
Lyapunov function (14)
Consider
the derivative of
Next, the sliding
control technique is designed to obtain the control signal of the system and
ensure that it achieves the ideal value. The system's virtual control signal
bias (16):
Choose slide (17):
Where
The
derivative of S is calculated (18):
As mentioned earlier,
one advantage of a DSC controller is its ability to avoid the phenomenon of
"term explosion" that occurs when the derivative of a virtual control
signal is calculated repeatedly in each cycle. In order to ensure system
stability and calculate the control signal, the value of Alpha is derived from
the first-order filter (13). Additionally, the second Lyapunov function is
selected (19):
The system's control signal will be
calculated in the form of a sliding controller to increase the system's
robustness against noise. Therefore, the control signal will include two
components TT, which is the control signal to keep the system state on the sliding
surface TR obtained from the condition
However
(20),
Theorem
3.1:
WMR described using the model (6) is controlled by (22) with
Proof:
The derivative
The advantage of the DSC method is to increase the
adaptability of the system and reduce the amount of controller computation. The
control signal used contains a sliding component, hence the robust stability of
the SMC. The low-pass filter used not only filters out endogenous
high-frequency noise but also provides information about the derivative of the
virtual control signal. Therefore, calculating the derivative of the virtual
control signal becomes unnecessary.
3.2.
Adaptive
fuzzy-sliding mode Design
During
the simulation to look for parameters suitable for slide controllers (Thi et al., 2019), I found that the adaptive slide controller
quality (13) largely depends on the selection of the control
parameter values, especially
Figure 2 Input fuzzy sets |
Table 1 Fuzzy inference coefficient for output
|
| ||||
NB |
NS |
Z |
PS |
PB | |
NB |
M(M) |
S(B) |
VS(VB) |
S(B) |
M(M) |
NS |
B(S) |
M(M) |
S(B) |
M(M) |
B(S) |
Z |
VS(VB) |
B(S) |
M(M) |
B(S) |
VS(VB) |
PS |
B(S) |
M(M) |
S(B) |
M(M) |
B(S) |
PB |
M(M) |
S(B) |
VS(VB) |
S(B) |
M(M) |
-
Fuzzy controller using
composition rule SumPROD
-
Defuzzification by the formula
From
equation (13), we have the control structure diagram as shown in Figure 3
below:
Figure 3 Structure diagram of an adaptive fuzzy sliding controller
4. Simulation of the
adaptive fuzzy-sliding controller for autonomous vehicles
Perform the simulation of
the proposed controller to control the motion of mobile robot with the
following parameters and trajectory: set the trajectory for the robot to move
Figure 4 Orbital response and orbital
deviation in simulation with m=10k |
Figure 5 Trajectory response and orbital
deviation when simulating with m=30kg and with noise |
Table 2 Trajectory
tracking simulation results of AFDSC controller
4.1. Experimenting with operating a mobile robot using an adaptive sliding-fuzzy controller combined with real math A*
Experiment
with the robot system, complete the hardware design and program the control algorithms on ROS
with the mobile robot model configured, as shown in Figure 6.
Figure
6
Schematic of the hardware structure to
control the self-propelled robot
The
mobile robot's steel body is constructed to specifications and measures 70 cm x
50 cm x 38 cm. Its 10-centimeter-wide tires can handle almost any indoor
surface. 12000-tick encoders are mounted on two motor shafts. The control
circuit hardware structure for the robot is used. Jetson Nano 4G (master)
high-performance processor, with the role of central processing, is a
specialized high-performance processor for artificial intelligence processing (WHO).
The microcontroller circuit (slave) (NCS uses ARM cortex M3 core STM32F407) is
the part that receives control signals from Jetson Nano 4G (master). The
H-bridge circuit (BTS7960 43A) uses MOSFETs as the power circuit to control the
4-wheel servo motors. The camera has a maximum RGB image resolution of up to
1280 x 720. RPLIDAR A1M8 360° Lidar is a laser scanner, which is combined with
the Astra 3D Camera that will send position, direction, and obstacle signals to
the Jetson Nano master processor and Sensor. The HWT901B IMU variable sends balanced
signals to the Jetson master processor.
Experiment for moving
robots to avoid static obstacles in the robot club room and technology 810_HA10
with scenario Starting
from the door to the middle of the room in front of the obstacle is a stack of
cartons. Perform robot control in 2 cases: A) Robot runs normally without load
(m = 10 kg); B) Robot runs with added load resistance (m=30kg).
To implement the global
migration planning approach, ROS provides three interfaces Areas include carrot_planner, navfn, and
global_planner. Including travel planning global transfer is the interface used to
execute the algorithm A * (Chung, Ojeda, and Borenstein. 2001). Algorithm A*
will be executed
by 2 nodes, a map (Map) and a location robot (Robot Pose), outputting data about the map and robot
position Figure 7.
The navigation system
designed in this paper combines information from encoder sensors, laser
scanning sensors, and IMUs. The structure diagram of the system in ROS is
developed using nodes, with each node having its own responsibility, services,
and functions. different services, and functions. The information exchanged
between each node is communicated through messages, the information transmitted
and received according to predefined protocols and a common standard for
communicating with external data packets. In addition, the tool supports visual
inspection of algorithms and data monitoring and ensures that data is processed
in real-time. The system structure diagram is designed on ROS including nodes
and the data transmission process is depicted as shown in Figure 8. Running the
experiment repeated 3 times for 2 cases (A and B) as suggested in the above
scenario, we can calculate the deviation between the real trajectory and the
planned trajectory as shown in Table 3.
Figure
7 WMR control
structure diagram with AFDSC controller combined with A* algorithm
Figure 8
Map button and location used in ROS
Figure 9 (a) Experimental image of mobile robot motion without load (m = 10 kg) and (b) Experimental image of mobile robot movement when there is an additional load (m = 30 kg)
Table 3 Trajectory
deviation results when running experiments
Run
times |
A |
Obstacle
avoidance time (s) |
B |
Obstacle
avoidance time(s) | ||||
|
|
|
|
|
| |||
1 |
0.0062 |
0.0045 |
0.0037 |
0.8102 |
0.0102 |
0.0075 |
0.0053 |
1.0032 |
2 |
0.0065 |
0.0051 |
0.0031 |
0.7834 |
0.0095 |
0.0081 |
0.0049 |
1.2143 |
3 |
0.0071 |
0.0042 |
0.0040 |
0.8621 |
0.0105 |
0.0069 |
0.0051 |
1.7302 |
5.
Evaluate
simulation results and experimental results
The
results show in Figure 9(a), 9(b), and Table 2 that in both cases, the
controller is guaranteed to follow the set trajectory, but the setting time and
the error value are slightly different. Specifically, with the same controller
as well as controller parameters, in the case of no external interference, the
orbital response approaches the set orbit after about 0.4 seconds with a very
small deviation of 0.0038 (m). Meanwhile, with changing model parameters and
adding uncertainty, the system is only stable after 0.8 seconds and the
determination error is 0.0063 (m). Whenever there is a change in the bias and
the bias derivative, the fuzzy rules are specifically designed to update the
parameters of DSC online. The newly proposed AFDSC set guarantees improved
quality in tracking the system's preset orbit. It enables faster attainment of
the set orbit and reduces the tracking error as well. However, the model deviation is large and
contains many factors uncertainty and noise. These factors, which affect the
robot with large amplitudes, mean that AFDSC no longer ensures quality. This
will be the next research direction of the author group.
The
results are shown in Table 2. The goal of the experiment was to successfully
verify the proposed algorithms through experimentation. To achieve this, the
robot is equipped with high-performance hardware and processing control
circuits, as well as programming support software based on the ROS robot
operating system. Synchronously design and manufacture hardware and peripheral
devices, manufacture electronic circuits, control, and peripheral communication
to be fast and strong enough to be expandable and upgradeable. Design
structure, program, install researched algorithms for robots, run tests, and
evaluate results. The experimental results show the correctness of the
theoretical analysis, the effectiveness of the proposed controller, and the
possibility of practical application. Experimental results show that when the
robot encounters an obstacle, it takes about 0.7834 to 1.7302 s to change the
local trajectory to avoid the obstacle. With the obstacle fixed in the
corridor, it shows the robot's responsiveness when moving flexibly to avoid
obstructions, calculate the optimal local trajectory, and navigate along the
local trajectory new with the allowed distance and distance and the movement
follows the specified trajectory with the position error in the x-axis from
0.0062 to 0.0105 m, the y-axis from 0.0042 to 0.0069 m, and from 0.0031 to
0.0053 rad.
This article successfully achieves
the goal of researching and proposing an algorithm based on the DSC (Dynamic
Sliding Surface Control) algorithm for differential self-propelled robots navigating
uncertain routes in a non-linear system. The algorithm focuses on improving
tracking quality and adapting to changes in robot parameters, as the robot
interacts with various objects and environments, and operates under noise on
different terrains. This algorithm takes advantage of efficiency DSC uses fuzzy
logic to adaptively adjust the coefficients of the virtual control signal and keeps
the system's status signal on the sliding surface to overcome the
disadvantages. DSC instability when encountering this state. This algorithm has
not been installed on any robot before at home or abroad, has high flexibility,
a simple structure, and is easy to program and install on the microprocessor.
It can adapt and Maximize efficiency by using the DSC platform it is especially
suitable for differential self-propelled robot models based on simulation
results and experimental runs. The next research direction of the authors is to
continue researching and improving adaptive algorithms when robots move on
sloping terrain (3D), as well as have movement patterns suitable for different
types of terrain with different complexities when operating in actual applications.
Optimize processing time, apply the ROS robot programming operating system for
intelligent programming, improving the system's tracking speed.
Aldo, J., Vicente, P., Anand, S., Juan, D., 2021. Adaptive Fuzzy Velocity Field Control for Navigation of Nonholonomic Mobile Robots. Journal of Intelligent & Robotic Systems, Volume 101, p. 8
Alshammrei, S., Boubaker, S., Kolsi, L., 2022. Improved Dijkstra Algorithm for Mobile Robot Path Planning and Obstacle Avoidance. Computers, Materials & Continua, Volume 72(3), pp. 5939–5954
Attia, H., Suan, S.T.K., 2024. Robust Sliding Mode Controller Design for Boost Converter Applications. International Journal of Technology, Volume 15(3), pp. 481–491
Bayar, G., Bergerman, M., Konukseven, E., Koku, A.B., 2016. Improving The Trajectory Tracking Performance of Autonomous Orchard Vehicles Using Wheel Slip Compensation. Biosystems Engineering, Volume 146, p. 149–164
Chen, C., Gao, H., Ding, L., Li, W., Yu, H., Deng, Z., 2018. Trajectory Tracking Control of WMRs with Lateral And Longitudinal Slippage Based on Active Disturbance Rejection Control. Robotics and Autonomous Systems, Volume 107, pp. 236–245
Chen, C., Li, T., Yeh, Y., Chang, C., 2009. Design and Implementation of An Adaptive Sliding-Mode Dynamic Controller For Wheeled Mobile Robots. Mechatronics, Volume19(2), pp. 156–166
Chung, H., Ojeda, L., Borenstein, J., 2001. Sensor Fusion for Mobile Robot Dead-Reckoning With a Precision-Calibrated Fiber Optic Gyroscope. In: Proceedings 2001 ICRA. IEEE International Conference on Robotics and Automation, Volume 4, pp. 3588–3593
Chwa, D.K., 2004. Sliding-Mode Tracking Control Of Nonholonomic Wheeled Mobile Robots In Polar Coordinates. IEEE Transactions on Control Systems Technology, Volume 12(4), pp. 637–644
Edalati, L., Sedigh, A.K., Shooredeli, M.A., Moarefianpour, A., 2018. Adaptive Fuzzy Dynamic Surface Control of Nonlinear Systems With Input Saturation and Time-Varying Output Constraints. Mechanical Systems and Signal Process, Volume 100, p. 311–329
Elsayed, M., Soe, M.T., Kit, W.W., Abdalla, H., 2019. An Innovative Approach to Developing a 3D Virtual Map Creator using an Ultrasonic Sensor Array. International Journal of Technology, Volume 10(7), pp. 1344–1354
Feng, X., Wang, C., 2021. Robust Adaptive Terminal Sliding Mode Control of an Omnidirectional Mobile Robot for Aircraft Skin Inspection. International Journal of Control, Automation and Systems, Volume 19, pp. 1078–1088
Gore, R., Reynolds Jr, P.F., Kamensky, D., Diallo, S., Padilla, J., 2015. Statistical Debugging For Simulations. ACM Transactions on Modeling and Computer Simulation (TOMACS), Volume 25(3), pp. 1–26
Hoang, N., Kang, H., 2016. Neural Network-Based Adaptive Tracking Control of Mobile Robots in The Presence of Wheel Slip and External Disturbance Force. Neurocomputing, Volume 188, pp. 12–22
Hou, Y., Gao, H., Wang, Z., Du, C., 2022. Path Planning for Mobile Robots Based on Improved A* Algorithm. In: International Conference on Neural Computing for Advanced Applications, Volume 1637, pp. 169–183
Jiang, Z.P., 2000. Robust Exponential Regulation of Nonholonomic Systems With Uncertainties. Automatic, Volume 36(2), pp. 189–209
Lenain, R., Thuilot, B., Cariou, C., Martinet, P., 2010. Mixed Kinematic and Dynamic Sideslip Angle Observer for Accurate Control of Fast Off-Road Mobile Robots. Journal of Field Robotics, Volume 27, pp. 181–196
Li, Y., Wang, Z., Zhu, L., 2010. Adaptive Neural Network PID Sliding Mode Dynamic Control of Nonholonomic Mobile Robot. In: Proceedings of the 2010 IEEE International Conference on Information and Automation, Harbin, China, pp. 753–757
Liu, C., Xie, S., Sui, X., Huang, Y., Ma, X., Guo, N., Yang, F., 2023. PRM-D* Method for Mobile Robot Path Planning. Sensors, Volume 23(7), p. 3512
Liu, J., Wang, Z., Zhang, L., Walker, P., 2021. Sideslip Angle Estimation of Ground Vehicles: A Comparative Study. IET Control Theory Application, Volume 14, pp. 3490–3505
Low, C.B., Wang, D., 2008. GPS-Based Tracking Control For A Car-Like Wheeled Mobile Robot With Skidding and Slipping. IEEE/ASME Transactions on Mechatronics, Volume 13(4), p. 480–484.
Mohareri, O., 2009. Mobile Robot Trajectory Tracking Using Neural Networks. Doctoral Dissertation, American University of Rajah
Nardênio, AM., Douglas, WB., 2021. Wheeled Mobile Robot Control: Theory, Simulation, and Experimentation. Springer
Nguyen, T., Nguyentien, K., Do, T., Pham, T., 2018. Neural Network-based Adaptive Sliding Mode Control Method for Tracking of a Nonholonomic Wheeled Mobile Robot with Unknown Wheel Slips, Model Uncertainties, and Unknown Bounded External Disturbances. Acta Polytechnica Hungarica, Volume 15, pp. 103–123
Park, B.S., Yoo, S.J., Park, J.B., Choi, Y.H., 2009. Adaptive Neural Sliding Mode Control Of Nonholonomic Wheeled Mobile Robots With Model Uncertainty. IEEE Transactions on Control Systems Technology, Volume 17(1), pp. 207–214
Qi, S., Zhang, D., Guo, L., Wu, L., 2018. Adaptive Dynamic Surface Control of Nonlinear Switched Systems with Prescribed Performance. Journal of Dynamical and Control Systems, Volume 24, pp. 269–286
Rabbani, M.J., Memon, A.Y., 2021. Trajectory Tracking and Stabilization of Nonholonomic Wheeled Mobile Robot Using Recursive Integral Backstepping Control. Electronics, Volume 10(16), pp. 1–22
Rahman, A., Hassan, N., Ihsan, S.I., 2022. Fuzzy Logic Controlled Two Speed Electromagnetic Gearbox for Electric Vehicle. International Journal of Technology, Volume 13(2), pp. 297–309
Rubio, F., Valero, F., Llopis-Albert, C., 2019. A Review of Mobile Robots: Concepts, Methods, Theoretical Framework, and Applications. Sage Journal, Volume 16(2), p. 1729881419839596
Rusdinar, A., Purnama, I., Fuadi, A.Z., Adiluhung, H., Wicaksono, M., Risnanda, Ningrum, R.A., 2021. Automated Ultraviolet C Light Mobile Robot for Room Sterilization and Disinfection. International Journal of Technology, Volume 12(4), pp. 854–864
Thi, K.D.H., Nguyen, M.C., Vo, H.T., Nguyen, D.D., Bui, A.D., 2019. Trajectory Tracking Control For Four-Wheeled Omnidirectional Mobile Robot Using Backstepping Technique Aggregated With Sliding Mode Control. In: 2019 First International Symposium on Instrumentation, Control, Artificial Intelligence, and Robotics (ICA-SYMP), pp. 131–134
Wang, C., Wang, D., Han, Y., 2021. Neural Network Based Adaptive Dynamic Surface Control for Omnidirectional Mobile Robots Tracking Control with Full-State Constraints and Input Saturation. International Journal of Control, Automation and Systems, Volume 19(12), pp. s4067–s4077
Xin, L., Wang, Q., She, J., Li, Y., 2016. Robust Adaptive Tracking Control Of Wheeled Mobile Robot. Robotics and Autonomous Systems, Volume 78, pp. 36–48
Xu, Z., Yang, S.X., Gadsden, S.A., 2020. Enhanced Bioinspired Backstepping Control for a Mobile Robot with Unscented Kalman Filter. IEEE Access, Volume 8, pp. 125899-125908
Ye, H., Wang, S., 2020. Trajectory Tracking Control for Nonholonomic Wheeled Mobile Robots with External Disturbances and Parameter Uncertainties. International Journal of Control, Automation and Systems, Volume 18, pp. 3015–3022
Zhang, J.J., Fang, Z.L., Zhang, Z.Q., Gao, R.Z., Zhang, S.B., 2022. Trajectory Tracking Control of Nonholonomic Wheeled Mobile Robots Using Model Predictive Control Subjected to Lyapunov-Based Input Constraints. International Journal of Control, Automation and Systems, Volume 20(5), pp. 1640–1651
Zhang, L., Chen, H., Huang, Y., Guo, H., Sun, H., Ding, H., Wang, N., 2020. Model Predictive Control For Integrated Longitudinal and Lateral Stability of Electric Vehicles With In-Wheel Motors. Emerg. IET Control Theory & Applications, Volume 14(18), pp. 2741–2751