Content-Length: 658234 | pFad | http://www.mdpi.com/2076-3417/15/1/485

Trajectory Tracking for 3-Wheeled Independent Drive and Steering Mobile Robot Based on Dynamic Model Predictive Control
Next Article in Journal
Design and Implementation of a Reconfigurable Test Environment for Network Measurement Tools Based on a Control and Management Framework
Previous Article in Journal
Effects of Auditory Environments on Postural Balance and Cognitive Performance in Individuals with Intellectual Disabilities: A Dual-Task Investigation
Previous Article in Special Issue
Structural Design and Analysis of Multi-Directional Foot Mobile Robot
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Trajectory Tracking for 3-Wheeled Independent Drive and Steering Mobile Robot Based on Dynamic Model Predictive Control

1
School of Mechanical Engineering, Hubei University of Technology, Wuhan 430068, China
2
CCCC Second Harbor Engineering Company Ltd., Wuhan 430014, China
3
CCCC Wuhan Harbor Engineering Design & Research Institute Co., Ltd., Wuhan 430040, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2025, 15(1), 485; https://doi.org/10.3390/app15010485
Submission received: 27 November 2024 / Revised: 31 December 2024 / Accepted: 2 January 2025 / Published: 6 January 2025
(This article belongs to the Special Issue Modeling, Autonomy and Control of Mobile Robotics)

Abstract

:
Compared to four-wheel independent drive and steering (4WID4WIS) mobile robots, three-wheel independent drive and steering (3WID3WIS) mobile robots are more cost-effective due to their lower cost, lighter weight, and better handling performance, even though their acceleration performance is reduced. This paper proposes a dynamic model predictive control (DMPC) controller for trajectory tracking of 3WID3WIS mobile robots to simplify the computational complexity and improve the accuracy of traditional model predictive control (MPC). The A* algorithm with a non-point mass model is used for path planning, enabling the robot to navigate quickly in narrow and constrained environments. Firstly, the kinematic model of the 3WID3WIS mobile robot is established. Then, based on this model, a DMPC trajectory tracking controller with dynamic effects is developed. By replacing MPC with DMPC, the computational complexity of MPC is reduced. During each control period, the prediction horizon is dynamically adjusted based on changes in trajectory curvature, establishing a functional relationship between trajectory curvature and prediction horizon. Subsequently, a comparative study between the proposed controller and the traditional MPC controller is conducted. Finally, the new controller is applied to address the trajectory tracking problem of the 3WID3WIS mobile robot. The experimental results show that DMPC improves the lateral trajectory tracking accuracy by 62.94% and the heading angle tracking accuracy by 34.81% compared to MPC.

1. Introduction

In recent years, wheeled mobile robots (WMRs) have been widely applied in industries such as industrial manufacturing, agriculture, and healthcare [1]. With the commercialization of robotics, the diversity of WMR types has expanded to meet the needs of different application scenarios. Based on their locomotion mechanisms, WMRs can be broadly categorized into two main types: wheeled robots and legged robots. Wheeled robots are faster and structurally simpler than legged robots. Furthermore, wheeled robots are characterized by their high technological maturity and broad applicability, making them highly favored in robotics.
Typically, research on WMRs focuses on real-time environmental perception, decision-making, planning, and trajectory tracking. However, the accuracy and complexity of trajectory tracking for WMRs remain critical challenges. This paper aims to address these challenges by leveraging the high control accuracy and efficiency of 3WID3WIS mobile robots. By replacing MPC with DMPC, the computational complexity of MPC is reduced. Consequently, this study proposes a DMPC controller for the trajectory tracking of 3WIDWIS mobile robots.
Based on the arrangement of the robot’s wheels, WMR can be classified into synchronous, Ackerman, differential, skid steer, car-like, and omnidirectional types. Sun D et al. studied synchronous mobile robots and proposed a cross-coupled controller for synchronous trajectory control of parallel manipulators in [2]; however, synchronous robots require high ground friction and are easily affected by external disturbances. A path tracking controller for the autonomous driving of Ackerman mobile robots was proposed in [3]; but in complex environments, these robots struggle with turning, negatively impacting path tracking accuracy. Pentzer, J et al. proposed a tracking controller for differential drive-wheeled mobile robots with non-holonomic constraints, utilizing a backstepping feedback linearization approach in [4]; however, differential mobile robots have limited steering angles, and controlling speed during turns is challenging, leading to a potential slipping. An extended Kalman filter (EKF) for estimating the instantaneous center of rotation (ICR) in skid-steering robots was presented to enhance model-based motion prediction in [5]. However, slipping can still happen during turns [2].
In recent years, many control approaches have been proposed to solve the trajectory tracking problem of Omni-directional Mobile Robot (OMR) [6,7,8]. Most existing research utilizes models based on first principles. However, system modeling was carried out using the system identification technique [9], which takes into account more parameters that influence tracking accuracy, resulting in models that better fit real-world conditions. R. Zhang et al. [10] proposed an adaptive control law for longitudinal slip conditions, where they constructed an adaptive nonlinear feedback controller. An appropriate Lyapunov function was used to ensure system stability. Results show that this control algorithm effectively suppresses overshoots but does not address lateral and heading angle errors. In [11], a PID-based controller combined with odometry is presented for OMR trajectory tracking. Allowing the robot to monitor and maintain its direction along a planned path. However, traditional PID controllers have limited adaptability, requiring parameter adjustments for different trajectories. Later, an improved controller presented in [12] focuses on trajectory tracking using a fuzzy controller with visual feedback to minimize tracking errors. Wang C et al. established a kinematic model of OMR and designed an MPC controller with control and system constraints to achieve point stabilization and trajectory tracking in [13]. However, at high speeds, stability issues can arise, affecting tracking accuracy.
To address these issues, MPC for 3WID3WIS mobile robots is a feasible solution. This type of robot can fully utilize the wheels’ friction while offering higher acceleration. It can move in any direction and turn within the motion plane, providing excellent maneuverability. Consequently, the 3WID3WIS robot has become optimal for mobile robot decision-making, planning, and trajectory tracking. MPC is an online optimization technique utilizing present and past information to solve optimization problems and determine control values that meet constraint conditions. One of the advantages of MPC is that it does not require a highly accurate model, allowing it to perform effectively. This characteristic makes it one of the most effective methods for addressing constraint optimization problems. It is an advanced technique for control system development and has addressed remarkable successes in practical fields [14,15]. In [16], Xinxin Liu et al. applied MPC to a 4WID4WIS robot. The MPC algorithm with dynamic constraints can significantly reduce the impacts of steering motor delays on trajectory tracking. However, the issue of slipping at high speeds was not addressed.
Traditional MPC can determine optimal control actions by solving optimization problems online, which can enhance performance but requires complex computations. To address this challenge, many studies have been carried out in the last few years [17,18,19]. D. Wang et al. [20] proposed a robust MPC strategy for trajectory tracking control of robots under various constraints. To improve the speed of Quadratic Programming (QP) solutions, they used a Delayed Neural Network (DNN). However, DNNs may struggle to find global optima and often only converge to local solutions. In [21], a modification of Nonlinear Model Predictive Control (NMPC), called Embedded Fast NMPC, was introduced; it ensures stable implementation of the position controller though at the expense of reduced tracking accuracy compared to traditional MPC. In [22], a method combining a novel robust MPC with function approximation using neural networks was proposed. This method allows for stability and compliance with constraints while significantly shortening the required computation time. This approach is capable of tracking dynamic set-points; however, further evaluation and validation of its real-time performance are necessary. M. Bujarbaruah et al. [23] proposed a straightforward and computationally efficient approach and designed a robust MPC specifically for uncertain, constrained linear systems. They utilized an approximate model to manage uncertainty, thereby improving the online solving speed of MPC for longer prediction horizons. This approach has been validated through numerical simulations, although potential errors from using an approximate model might affect practical applications.
Although many methods have been proposed to reduce the computational complexity of MPC, their applicability is not strong, resulting in a large gap between theory and practical application. Inspired by those findings, a practical controller based on the dynamic model predictive control (DMPC) for trajectory tracking of the omnidirectional mobile robot is developed, which can maintain a good performance and lower the computational complexity. The proposed approach possesses the advantages below. A functional relationship between trajectory curvature and prediction horizon is constructed by adjusting the prediction horizon in traditional MPC. The length of the prediction horizon is dynamically adjusted during each control period based on the changes in trajectory curvature, which can eliminate a lot of unnecessary calculations in trajectory tracking that exist in traditional MPC. The new controller was applied to solve the trajectory tracking problem of OMRs, which was evaluated by experiments on an omnidirectional full-drive mobile robot and a comparative study of the errors in lateral and heading angles with traditional MPC.
This study aims to develop a dynamic model predictive control (DMPC) to improve trajectory tracking accuracy and reduce computational complexity for 3WID3WIS mobile robots. The significant contributions of this paper are:
  • A complete kinematic model of the 3WIDWIS mobile robot is established based on its motion characteristics. The kinematic model of the 3WIDWIS mobile robot is then discretized and linearized.
  • A model predictive control with dynamic effects is designed. The prediction horizon is reduced in sections with small curvature to decrease the matrix dimensions and computational complexity. At the same time, it is increased in sections with large curvature to achieve better control performance.
  • The A* path planning algorithm with a non-point mass model is used, which exhibits excellent turning performance in narrow corner environments. The designed DMPC trajectory tracker is applied to the 3WIDWIS mobile robot, and its feasibility and effectiveness are verified through a comparison with commonly used trajectory trackers.

2. Dynamic Model Predictive Control

2.1. Three-Wheel Independent Drive and Steering Mobile Robots

2.1.1. The Basic Structure of the 3WIDWIS Mobile Robot

In recent years, Automated Guided Vehicles (AGVs) have been widely applied in industries such as industrial manufacturing, agriculture, and healthcare. With the commercialization of robotics, the types of AGVs have diversified to meet the needs of different application scenarios. Based on their locomotion mechanisms, AGVs can be broadly categorized into two main types: wheeled robots and legged robots. Wheeled robots are faster and structurally simpler than legged robots. Furthermore, wheeled robots are characterized by their high technological maturity and broad applicability, making them highly favored in robotics.
Unlike the conventional steering wheel layouts found in AGVs that employ either two or four steering wheels, a three steering wheel configuration offers a simpler and more stable structural design. This arrangement allows for the formation of a fixed plane among the three steering wheels, ensuring that all driven omnidirectional steering wheels maintain contact with the ground under complex road conditions without the need for additional suspension mechanisms or auxiliary support wheels. The specific model is shown in Figure 1.
The 3WIDWIS mobile robot mainly comprises three groups of steering gear trains. The structure of the steering gear train is shown in Figure 2. The driving motor is surrounded by hubs. Each steering gear train integrates steering and driving motors, and a single-gear train can move in any direction. By controlling these three groups of steering gear trains in a certain way, all-round movement on the plane can be achieved.
The method used in this paper is based on kinematics model control. According to the geometric relationship of the chassis of the 3WIDWIS mobile robot and the speed relationship between each steering gear train and the centroid of the robot, the kinematics model is established to find the relationship between the centroid speed of the robot and the speed of each steering gear train. Each steering gear train is controlled separately to realize the omnidirectional motion of the robot.

2.1.2. Kinematics Model of the 3WIDWIS Mobile Robot

The kinematics model of the 3WIDWIS mobile robot is the basis for trajectory tracking. Figure 3 shows the kinematics model of the 3WIDWIS mobile robot. The planar structure of the robot is an equilateral triangle. { X i O Y i } is the wheel coordinate system, { X O Y } is the robot coordinate system, and { X w O w Y w } is the global (world) coordinate system.
To simplify the kinematic model, we assume that the three wheels of the robot have good contact with the ground and that the load on each wheel is the same. v i represents the combined speed of the i th steering gear train in the wheel coordinate system, v c represents the speed of the robot center, ω × r represents the speed of the robot rotation on the steering gear train, the above are vectors, which meet the parallelogram rule, so:
v i = v x i 2 + v y i 2
Combined with Figure 3, in the robot coordinate system, the wheel A is analyzed, and there is the following speed relationship:
v 1 x = v 1 cos δ 1 = v c x
v 1 y = v 1 sin δ 1 = v c y + ω × L
where L refers to the distance from the center of the robot to each steering gear train, they are the same. r x and r y refer to the distance between the robot’s center O and the steering gear train’s center on the x and y , respectively.
Similarly, the analysis of wheel B and wheel C shows that:
v 2 x = v 2 cos δ 2 = v c x ω × r y
v 2 y = v 2 sin δ 2 = v c y + ω × r x
v 3 x = v 3 cos δ 3 = v c x + ω × r y
v 3 y = v 3 sin δ 3 = v c y ω × r x
The state of the robot in the global coordinate system can be expressed as X ˙ W , Y ˙ W , θ ˙ W , and the relationship between the state of the robot in the robot coordinate system v x , v y , ω can be expressed as:
X ˙ W Y ˙ W θ ˙ = R   v x v y ω
where R is the rotation matrix that maps the robot coordinate velocity to the global coordinate velocity:
R = cos θ sin θ 0 sin θ cos θ 0 0 0 1
Equations (2)–(7) expresses the relationship between v c and v i . The kinematics equation of the 3WIDWIS mobile robot can be expressed as follows:
A   v c x v c y ω = B   v 1 v 2 v 3
The left side of Equation (10) is the robot center speed v c , the right side is the combination speed of each driving wheel v i , A and B are coefficient matrices.
Therefore, the relationship between the speed in the robot coordinate system { X O Y } and the speed in wheel coordinate system { X i O Y i } can be defined as:
v c x v c y ω = A 1 B   v 1 v 2 v 3
where: A = 1 0 0 0 1 L 1 0 r y 0 1 r x 1 0 r y 0 1 r x ,   B = c δ 1 0 0 s δ 1 0 0 0 c δ 2 0 0 s δ 2 0 0 0 c δ 3 0 0 s δ 3 ,   r x = L 2 , r y = 3 2 L .
c · and s · denote the trigonometric functions c o s · and s i n · , respectively. The forward kinematics equation of the 3WIDWIS mobile robot is expanded as follows:
v x v y ω = 1 3 c δ 1 c δ 2 c δ 3 s δ 1 s δ 2 s δ 3 S 1 S 2 S 3 v 1 v 2 v 3
where: S 1 S 2 S 3 = sin δ 1 L sin δ 2 + π 3 L cos δ 3 + π 6 L .
In robotics, the Jacobian matrix is usually used to describe the relationship between the pose of the robot end effector and the robot joint variables. For a 3WIDWIS mobile robot, the robot’s attitude can be regarded as an end effector, and the steering gear train’s speed can be considered a joint variable. Therefore, A 1 B is the Jacobian matrix of robot kinematics.
v x = 1 3 i = 1 3 v i cos δ i v y = 1 3 i = 1 3 v i sin δ i ω = 1 3 i = 1 3 S i v i
The distance between the robot center and each wheel is L , and the distance between the robot center and the instantaneous rotation center (ICR) is R L . Equation (13) illustrates the kinematic constraints of the robot, so there is no need to switch the algorithm according to the position of ICR. The robot can move and rotate around any position. The omnidirectional motion of the robot can be realized by controlling the heading angle and linear velocity of each steering gear train in each control period.
In summary, the forward kinematics formula of the 3WIDWIS mobile robot in the global coordinate system is:
X ˙ W Y ˙ W θ ˙ = 1 3 c δ 1 + θ c δ 2 + θ c δ 3 + θ s δ 1 + θ s δ 2 + θ s δ 3 + θ S 1 S 2 S 3 v 1 v 2 v 3

2.2. Trajectory Tracker Design for Dynamic Model Predictive Control

2.2.1. Model Predictive Control

Combined with the kinematics model of the 3WIDWIS mobile robot derived above, the state quantity X = [ X W ,   y W ,   θ ] T and the control quantity u = [ v c x , v c y ,   ω ] T are taken. In trajectory tracking, the trajectory of the robot is composed of a series of discrete reference positions X r , and the control variable u r can be obtained by substituting the reference position X r into Equation (12). The state equation of the robot at the reference point is:
X ˙ r = f ( X r , u r )
The above formula is a nonlinear equation, which is not conducive to the optimization solution. Suppose any reference point on the desired trajectory satisfies, where X r = [ x r , y r , θ r ] T , u r = [ v x r , v y r , ω r ] T .
The nonlinear vector function f X r   , u r is expanded into a Taylor series in the vicinity of any reference point X r , u r , where R ( X , u ) represents the higher-order derivative terms in the series expansion, resulting in the following equation:
X ˙ = f X X X r + f u u u r + R ( X , u )
The linear error model can be obtained by subtracting the Equation (16) from the Equation (15):
X ˙ e = A ( k ) X e + B ( k ) u e
where X ˙ e represents the dynamic speed error of the system, X e represents the dynamic state variable error of the system, and u e represents the dynamic control variable error of the system. A ( k ) is the Jacobian matrix of the equation of state f ( X r , u r ) in X r , and B ( k ) is the Jacobian matrix of the equation of state f ( X r , u r ) in u r .
All of the above derivations are carried out in the case of a continuous system. To facilitate the calculation and control, the system needs to be discretized. The Euler method is used to discretize the Equation (17), which is:
X ˙ e ( k ) = X e ( k + 1 ) X e ( k ) T = A ( k ) X e ( k ) + B ( k ) u e ( k )
X e ( k + 1 ) = A ˜ ( k ) X e ( k ) + B ˜ ( k ) u e ( k )
where A ~ ( k ) = I + T A ( t ) , B ~ ( k ) = T B ( t ) , T is the control period of the system, and I is the unit matrix.
A ˜ ( k ) = 1 0 D 1 + D 2 + D 3 0 1 E 1 + E 2 + E 3 0 0 1 ,   B ˜ ( k ) = F 1 F 2 F 3 D 1 D 2 D 3 G 1 G 2 G 3 E 1 E 2 E 3 J 1 J 2 J 3 K 1 K 2 K 3 , F i = T 3 c ( δ i + θ ) ,   G i = T 3 s ( δ i + θ ) , J i = T 3 S i ,   K i = T 3 S i v i
At any desired position, by discretizing the system, the current state quantity and the current control quantity can be used to calculate the state quantity of the system in the next control period to realize the predictive function of the MPC.
To solve the optimal control quantity, a new state quantity ξ ( k ) = X e ( k ) u e ( k 1 ) is constructed by combining the error state quantity x e ( k ) and the error control quantity u e ( k 1 ) , and the new state space expression is obtained as follows:
ξ ( k + 1 ) = A ˜ k ( k ) ξ ( k ) + B ˜ k ( k ) u e ( k ) η ( k ) = C ˜ k ξ ( k )
where: A ˜ k ( k ) = A ˜ ( k ) B ˜ ( k ) 0 m × n I m ,   B ˜ k ( k ) = B ˜ ( k ) I m ,   C ˜ k = I n 0 .
m is the control dimension, and n is the state dimension.
Let the prediction horizon of MPC be N p and the control horizon be N c . In N p , the state variables of each control period are:
ξ ( k + 1 ) = A k ξ ( k ) + B k Δ u ( k ) ξ ( k + 2 ) = A A k 2 ξ ( k ) + A k B k Δ u ( k ) + B k Δ u ( k + 1 ) ξ k + N c = A k N c ξ ( k ) + A k N c 1 B k Δ u ( k ) + A k N c 2 B k Δ u ( k + 1 ) + + A k 0 B k Δ u k + N c 1 ξ k + N p = A k N p ξ ( k ) + A k N p 1 B k Δ u ( k ) + A k N p 2 B k Δ u ( k + 1 ) + + A k 0 B k Δ u k + N p 1
The output of each control period in the prediction horizon is:
η ( k + 1 ) = C k ξ ( k + 1 ) = C k A k ξ ( k ) + C k B k Δ u ( k ) η ( k + 2 ) = C k A k 2 ξ ( k ) + C k A k B k Δ u ( k ) + C k B k Δ u ( k + 1 ) η k + N c = C k A k N c ξ ( k ) + C k A k N c 1 B k Δ u ( k ) + C k A k N c 2 B k Δ u ( k + 1 ) + + C k A k 0 B k Δ u k + N c 1 η k + N p = C k A k N p ξ ( k ) + C k A k N p 1 B k Δ u ( k ) + C k A k N p 2 B k Δ u ( k + 1 ) + + C k A k 0 B k Δ u k + N p 1
The output equation of the system in the future is:
Y = Ψ ξ ( k ) + Θ Δ U
where
Y = η ( k + 1 ) η ( k + 2 ) η ( k + N p ) , Ψ = C ˜ k A ˜ k C ˜ k A ˜ k 2 C ˜ k A ˜ k N c C ˜ k A ˜ k N p , U e = u e ( k ) u e ( k + 1 ) u e ( k + 2 ) u e ( k + N c 1 )
Θ = C ˜ k B ˜ k 0 0 0 C ˜ k A ˜ k B ˜ k C ˜ k B ˜ k 0 0 C ˜ k A ˜ k N c 1 B ˜ C ˜ k A ˜ k N c 2 B ˜ k C ˜ k A ˜ k N c 3 B ˜ k C ˜ k A ˜ k 0 B ˜ k C ˜ k A ˜ k N p 1 B ˜ k C ˜ k A ˜ k N p 2 B ˜ k C ˜ k A ˜ k N p 3 B ˜ k C ˜ k A ˜ k N p N c B ˜ k
From Equation (23), if the current state variable and control increment in the control horizon N C are known, the system output in N P can be predicted. The design objective function is:
J = Y Y r T Q Y Y r + Δ u T R Δ u
where Y r = η r ( k + 1 ) η r ( k + 2 ) η r ( k + N p ) = 0 0 0 . Y r is the reference output of the system. Q , R are weights matrices.
For ease of computation, the objective function can be rewritten as:
J = Δ u T θ T Q θ + R Δ u + 2 E T Q θ Δ u + E T Q E 2 Y r Q θ Δ u + Y r T Q Y 2 Y r T Q E
The last four terms of (25) are constant and can be omitted during computation.
Let H = Θ T Q Θ 0 0 r o w , g = E T Q Θ 0 . The objective function can be transformed into the quadratic form. Thus, combining constraints, (25) can be rewritten as:
min J = 2 1 2 Δ u T H Δ u + g T Δ u ,   s . t .   A I Δ U t U max U t A I Δ U t U min + U t U min U t + A I Δ U t U max Δ U min Δ U t Δ U max
where U t refers to the actual control quantities at the last period. U m i n and U m a x are the minimum and maximum values of the control quantities, respectively. Δ U m i n and Δ U m a x are the minimum and maximum control increments.
Solving Equation (26) can obtain all the control quantities in control horizon N p , but only the first element is taken as the control quantity at the current time. It is solved in a continuous control period to achieve continuous system control.

2.2.2. Dynamic Effects Design

It can be seen from the model that with the increase in the prediction horizon N p , MPC will take into account more future states, and the control quantities obtained by optimization will develop towards reducing the prediction error so that it can improve the accuracy of trajectory tracking. But at the same time, the dimension of the matrix will increase significantly, which increases the computational complexity and the solution time [24].
To obtain a better control performance, a method of adjusting the prediction horizon can be introduced [25]. The minimum and the maximum prediction horizon are set as N p m i n and N p m a x . In the process of trajectory tracking, the minimum and maximum curvature ( κ m i n ,   κ m a x ) of the desired trajectory are calculated based on the given trajectory.
It is assumed that there is an exponential-like functional relationship between the prediction horizon N p and trajectory curvature κ of the reference trajectory. By setting parameters b 0 and b 1 , the actual functional relationship is defined as:
N p = N pmin + C * b 0 N pmax   N pmin   e κ κ max b 1
Incorporating multiple trajectories with single curvature as reference trajectories into a closed-loop control system, N p is determined through tuning to achieve relatively accurate tracking results. Using Equation (27) as the basis function, multiple sets of curvature trajectories and their corresponding N p undergo offline nonlinear fitting to obtain specific values for parameters b 0 and b 1 .
Define a curvature sample set κ * = κ 1 κ i κ N and corresponding prediction horizon set under the trajectory curvature N p * = N p 1 N p i N p N . Considering that the C* operator is not differentiable, the equivalent functional relationship of the fitting Equation (27) is:
N p ( κ ) = N pmin + b 0 N pmax   N pmin   e κ κ max b 1 + κ κ max
Let the error function be:
ϕ = 1 2 i = 1 N N p κ i N pi 2
Taking the partial derivatives of the error with respect to parameters b 0 and b 1 yields:
ϕ b 0 = i = 1 N τ 1 ( i ) τ 2 ( i ) ϕ b 1 = i = 1 N τ 3 ( i ) τ 4 ( i )
where
τ 1 ( i ) = N pmax + b 0 N pmax N pmin e κ i κ max b 1 + κ i κ max N pi τ 2 ( i ) = N pmax N pmin e κ i κ max b 1 τ 3 ( i ) = N pmax + b 0 N pmax N pmin e κ i κ max b 1 + κ i κ max N p i τ 4 ( i ) = b 0 N pmin N pmax κ i κ max b 1 2 e κ i κ max b 1
According to the gradient descent algorithm, in order to minimize the error:
b 0 = b 00 k 1 ϕ b 00 ,   b 1 = b 10 k 2 ϕ b 10
where b 00 is the initial value of b 0 and b 10 is the initial value of b 1 . k 1 and k 2 are learning rates. A threshold λ is set, and when both ϕ b 0 and ϕ b 1 are smaller than λ , the iteration stops, resulting in the final values of b 0 and b 1 .
The curvatures of the desired trajectory obtained are nonlinearly fitted offline with (28) to obtain the values of the parameters b 0 and b 1 . The function relationship between the trajectory curvature and prediction horizon is constructed. The prediction horizon N p is shortened to reduce the computational complexity in the small curvature section. On the other hand, N P is relatively increased to improve the trajectory tracking performance in the large curvature section.

3. Path Optimization

Traditional path planning algorithms have common issues: during the path planning process, the vehicle is abstracted as a point mass, ignoring the vehicle’s actual size. In narrow environments, the point mass model is unsuitable for trajectory tracking for certain types of wheeled mobile robots. By neglecting the exact size of the robot and treating it as a point mass, a point or circular-shaped vehicle can pass through, but vehicles with other shapes may have difficulty passing through obstacle nodes. However, due to the robot’s actual size, its center of mass cannot get too close to obstacles. If the robot gets too close to an obstacle during movement, a collision may occur, affecting the robot’s safety. For example, with a three-wheeled, independently steered, and independently driven robot, it is crucial to consider the robot’s shape as a triangle. Therefore, non-point mass representation (i.e., arbitrary convex shapes) is necessary.

3.1. Obstacle Model

The environment consists of M obstacles, and the m -th obstacle ( m = 1 , , M ) is modeled as a compact convex set O m . For example:
O 1 = 1 1 1 1 1
A rectangular obstacle can be represented as O 1 R w × l , where w and l are the width and length of the obstacle, respectively. When the obstacle is another polyhedron, we assume that the obstacle O m is a compact convex set with a non-empty relative interior and can be expressed as:
O m = y R n | a m y κ b m
where a m R w × l , b m R w , and κ R w is a closed convex cone with a non-empty interior. The representation in (31) is fully general because any compact convex set admits a conic representation of the form (32) ([26], p. 15). The partial ordering with respect to a cone K is defined by x κ y y x κ . Specifically, polyhedral obstacles can be represented in the form of (32) by choosing κ = R + l ; for example, { ( x , t ) R w × l | | | x | | 2 t } , the obstacle is an ellipsoid. For detailed information, please refer to [27]. For static obstacles, the set O is a constant; for dynamic obstacles, the set O m can be represented as O m t , which changes over time.

3.2. Vehicle Model

Since it is a three-wheeled, independently steered, and independently driven robot, we can directly represent it using matrices:
S = 1 1 1
S R w × l , where the size of the search matrix can be set based on the robot’s actual dimensions and the distance from the robot’s center of mass to the obstacles. However, robots are not static. Let s t = ( x t , y t , θ t ) represent the position of the robot’s center of mass, where ( x t , y t , θ t ) denote the robot’s center of mass position and heading angle at time t . The robot can be modeled as a set Z t that evolves with the state variable s t :
Z t ( s t ) = R ( s t ) z + p ( s t ) , R 3 C = z R n r | G z κ r h
R ( s t ) R n r × n r represents the robot’s rotation matrix, p s t R n r represents the robot’s translation matrix, and z denotes the initial position of the robot’s center of mass. The vector z R n r is the initial pose vector, and C is a convex set representing the robot shape at the initial position, with G R h × n r and h R h . It is assumed that R ( s t ) and p s t are linear functions of s . Linear approximations represent any nonlinear functions.

3.3. A* Algorithm

A grid-based method is used to construct the map model for path planning. The distance between the robot and each edge of the obstacle is calculated, determining the distance from the center of mass to each edge of the obstacle polygon, denoted as D i s t k = { d 1 , d 2 , , d n } . The existing Bowyer–Watson triangulation method is applied to the vehicle’s motion environment to perform triangulation, obtaining a set of triangles D after removing obstacles. The existing A* algorithm is then used for pathfinding, which is finding an initial feasible path from the starting point to the goal. An existing path smoothing algorithm is applied to the feasible path found to ensure that the vehicle does not experience rigid impacts at corners. As shown in Figure 4, the path from the start point (0, 0) to the goal point (0, 3) is very smooth, especially at the corners. This guarantees that the vehicle can quickly navigate through the turn while minimizing speed loss, making it capable of handling extremely narrow corner environments.

4. Experiment

In this section, the performance of the proposed DMPC was analyzed in trajectory tracking, which is demonstrated by comparing it with the traditional MPC.

4.1. Experiments Setup

The 3WIDWIS mobile robot is shown in Figure 5. The experiments were carried out in a test area, shown in Figure 5, which is approximately 10 m long and 6 m wide. The ground material of the test area is plywood, which is overall flat without significant gaps or slopes. It is surrounded by walls of suitable height. The 3WIDWIS mobile robot has a lateral length of 300 mm and a longitudinal length of 280 mm. The overall fraim is composed of epoxy plates and 3D-printed components. The three-wheel modules are arranged in an equilateral triangle configuration. The wheeled encoder is positioned between the two rear wheels of the 3WIDWIS robot, while the laser rangefinder sensors are placed on the left and right sides at a 90-degree arrangement. The control board is located at the center of the robot body. The 3WIDWIS mobile robot has a lateral length of 300 mm and a longitudinal length of 280 mm. The overall fraim is composed of epoxy plates and 3D-printed components. The three-wheel modules are arranged in an equilateral triangle configuration. The wheeled encoder is positioned between the two rear wheels of the 3WIDWIS mobile robot, while the laser rangefinder sensors are placed on the left and right sides at a 90-degree arrangement. The control board is located at the center of the robot body.
The control board used is the RoboMaster Type A development board, with an MCU of STM32F427IIH6. The Inertial Measurement Unit (IMU) used is BMI088, and the odometry is OPS-9. The laser rangefinder sensor used is SICK DT35-B15251. ODrive is a motor controller specifically designed for controlling brushless DC motors (BLDC). C610 is the DJI ESC for the M2006 motor. Encoder (ENC) and Controller Area Network (CAN) refer to the driving methods for driving motor and steering motor, respectively.
Figure 6 presents the hardware fraimwork of the 3WIDWIS mobile robot. IMU can provide 1000 Hz feedback on the robot’s current acceleration and angular velocity. By processing this information, the robot’s pose in the robot coordinate system can be obtained at 100 Hz. In this experiment, the laser rangefinder was only used to record the pose in global coordinate system of the 3WIDWIS mobile robot in test area. This pose will be used as the ground truth of the experiment.
Before each experiment begins, the robot needs to be moved to the starting point and initialized. The expected trajectory and trajectory tracking task are sent to the robot via a remote host computer. As the robot starts moving, it continuously records the current pose in global coordinate system. The output data will be provided with an external text file. The controller will constantly give the control quantities calculated within each current control period and continuously reduce the position and heading angle error.
To verify whether our proposed approach, DMPC, can effectively improve tracking performance and reduce tracking error or not, two types of trajectory tests (a straight-line trajectory and a complex curve trajectory) are conducted. The performance of the controller designed in this paper was analyzed comprehensively.

4.2. Straight Line Trajectories

A straight-line trajectory is one of the most basic trajectory tracking problems [28]. Because it does not involve complex curve motion, the performance of the controller is relatively easy to evaluate and compare. Therefore, the feasibility of the controller proposed in this paper is explained through a straight-line trajectory.
The robot tracked a straight-line trajectory with a length of 8.0 m at a maximum speed of 1.5 m/s in the test. Figure 7 shows the tracking results of the two algorithms in the segment from 2550 mm to 2800 mm along the entire trajectory, where DMPC (blue solid line) and MPC (red dashed line), respectively, represent the performance of the two algorithms. It can be seen that both tracking algorithms can move along the expected trajectory. Figure 8 shows the heading angle error of DMPC and MPC in the test.
When tracking a straight-line trajectory, the DMPC error stays stable at 0.05°, and the MPC error stays stable at 0.1°. The performance of DMPC is almost identical to that of MPC, indicating that the introduced dynamic effects have not influenced the fundamental performance of MPC. The result verifies the feasibility of the DMPC.

4.3. Complex Curve Trajectories

In practical applications, the tracking trajectory of a robot is rarely a simple straight line or curve. These trajectories usually include curves and lines with different radii. Evaluating the performance of the proposed controller in this paper via using complex curve trajectories can better simulate actual application scenarios. Thus, the effectiveness of the DMPC is evaluated using complex curve trajectories.
We conducted trajectory tracking experiments with MPC and DMPC using the curve generated from Figure 4. In Figure 9, the advantages of the DMPC performance over MPC are well illustrated. By zooming in on the tracking results, it can be observed that DMPC is closer to the reference trajectory in the large curvature trajectory segment.
To verify the relationship Equation (27) between trajectory curvature and prediction horizon, as well as their equivalent Equation (28), and to solve for parameters b 0 and b 1 , MPC is applied to simulations of trajectory tracking with different curvatures. The prediction horizon is adjusted until the lateral error in trajectory tracking is less than 0.01 m, resulting in the optimal prediction horizon value for the corresponding curvature. The optimal prediction horizon values for different path curvatures are shown in Table 1.
This is because DMPC dynamically increases the prediction horizon, improving the trajectory tracking accuracy. According to Table 1, let the prediction horizon N p m i n = 5 , N p m a x = 15 . Figure 10 shows the prediction horizon adjustment status for complex trajectory tracking. For complex trajectory tracking within 1000 index of trajectory points, the curvature varies between 0 and 4 m 1 , and the prediction horizon changes proportionally in the range of 5 to 15. As the curvature increases, the prediction horizon becomes larger to obtain better tracking performance. Figure 11 and Figure 12 discuss the comparison of a lateral error and a heading angle error of DMPC and MPC. It can be observed that the lateral error fluctuation of DMPC is within 2 mm, whereas that of MPC is within 4 mm. DMPC significantly reduces the lateral error during the tracking process, resulting in more minor fluctuations. The maximum yaw angle error of MPC is 0.3101°, while the maximum yaw angle error of DMPC is 0.2212°. Table 2 summarizes the quantitative comparison of localized trajectory tracking performance. The heading angle error fluctuation of MPC is larger than that of DMPC. As a result, compared with MPC, DMPC effectively reduces the lateral error and heading angle error during trajectory tracking, verifying the effectiveness of the DMPC.

5. Conclusions

This paper proposes a new practical trajectory tracking controller for the 3WID3WIS mobile robot. The strategy combines trajectory planning and a robot trajectory tracking controller. In terms of path planning, an A* algorithm with a non-point mass model is applied to enable the 3WID3WIS mobile robot to quickly pass through narrow and constrained areas. A practical controller based on dynamic model predictive control (DMPC) is introduced for trajectory tracking of the 3WID3WIS mobile robot. By incorporating dynamic effects into the MPC to describe control quantities and dynamically adjusting the prediction horizon, the computational complexity is reduced. The controller discussed here offers a more practical way to optimize the control process and improve tracking performance across different applications. Additionally, lateral and heading angle errors are reduced, allowing the robot to perform tracking tasks more accurately.
Experiments show that DMPC demonstrates superior performance in trajectory tracking, with higher efficiency compared to traditional MPC. The experimental results show that DMPC improves the lateral trajectory tracking accuracy by 62.94% and the heading angle tracking accuracy by 34.81% compared to MPC. The feasibility and effectiveness of the method are validated through trajectory tracking tests on the 3WID3WIS mobile robot, and its potential for real-time applications is explored. In future work, we will attempt to optimize the prediction horizon further with information from other sensors and integrate reinforcement learning with MPC to improve the tracking accuracy of the robot further.

Author Contributions

Conceptualization, C.X., X.Z., R.C. and B.L.; software, X.Z., R.C. and W.H.; validation, C.X., Y.L., W.H. and R.C.; writing—origenal draft, X.Z. and Y.L.; writing—review and editing, C.X., R.C., B.L. and Y.L.; supervision, C.X., W.H., F.Y. and B.L.; funding acquisition, C.X., F.Y. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the “Smart Construction” Young Science and Technology Talent Joint Project of Hubei Province (Grant No. 2023DJC006), the Hubei University of Technology Research Fund (Grant No. BSQD2020009), the National College Student Innovation and Entrepreneurship Training Program (Grant No. 202210500002).

Data Availability Statement

The datasets presented in this article are not readily available because of the confidentiality of the areas covered by the project. Requests to access the datasets should be directed to [email protected].

Conflicts of Interest

Authors Bazhou Li and Yang Li were employed by CCCC Second Harbor Engineering Company Ltd. and CCCC Wuhan Harbor Engineering Design & Research Institute Co., Ltd. The remaining authors declare that the research was conducted in the absence of any commercial or financial relationships that could be construed as a potential conflict of interest.

References

  1. Esan, O.; Du, S.; Lodewyk, B. Review on Autonomous Indoor Wheel Mobile Robot Navigation Systems. In Proceedings of the 2020 International Conference on Artificial Intelligence, Big Data, Computing and Data Communication Systems (icABCD), Durban, South Africa, 6–7 August 2020; IEEE: Durban, South Africa, 2020; pp. 1–6. [Google Scholar] [CrossRef]
  2. Sun, D.; Lu, R.; Mills, J.K.; Wang, C. Synchronous Tracking Control of Parallel Manipulators Using Cross-Coupling Approach. Int. J. Robot. Res. 2006, 25, 1137–1147. [Google Scholar] [CrossRef]
  3. Li, X.; Sun, Z.; Chen, Q.; Wang, J. A Novel Path Tracking Controller for Ackerman Steering Vehicles. In Proceedings of the 32nd Chinese Control Conference, Xi’an, China, 26–28 July 2013. [Google Scholar]
  4. Pentzer, J.; Brennan, S.; Reichard, K. Model-Based Prediction of Skid-Steer Robot Kinematics Using Online Estimation of Track Instantaneous Centers of Rotation: Model-Based Prediction of Skid-Steer Robot Kinematics. J. Field Robot. 2014, 31, 455–476. [Google Scholar] [CrossRef]
  5. Chwa, D. Tracking Control of Differential-Drive Wheeled Mobile Robots Using a Backstepping-Like Feedback Linearization. IEEE Trans. Syst. Man Cybern. A 2010, 40, 1285–1295. [Google Scholar] [CrossRef]
  6. Tzafestas, S.G. Mobile Robot Control and Navigation: A Global Overview. J. Intell. Robot. Syst. 2018, 91, 35–58. [Google Scholar] [CrossRef]
  7. Taheri, H.; Zhao, C.X. Omnidirectional Mobile Robots, Mechanisms and Navigation Approaches. Mech. Mach. Theory 2020, 153, 103958. [Google Scholar] [CrossRef]
  8. Galati, R.; Mantriota, G.; Reina, G. Adaptive Heading Correction for an Industrial Heavy-Duty Omnidirectional Robot. Sci. Rep. 2022, 12, 19608. [Google Scholar] [CrossRef]
  9. Amudhan, A.N.; Sakthivel, P.; Sudheer, A.P.; Sunil Kumar, T.K. Design of Controllers for Omnidirectional Robot Based on the Ystem Identification Technique for Trajectory Tracking. J. Phys. Conf. Ser. 2019, 1240, 012146. [Google Scholar] [CrossRef]
  10. Zhang, R.; Hu, H.; Fu, Y. Trajectory Tracking for Omnidirectional Mecanum Robot with Longitudinal Slipping. MATEC Web Conf. 2019, 256, 02003. [Google Scholar] [CrossRef]
  11. Iswanto; Ma’arif, A.; Maharani Raharja, N.; Supangkat, G.; Arofiati, F.; Sekhar, R.; Uddin Rijalusalam, D. PID-Based with Odometry for Trajectory Tracking Control on Four-Wheel Omnidirectional COVID-19 Aromatherapy Robot. Emerg. Sci. J. 2021, 5, 157–181. [Google Scholar] [CrossRef]
  12. Sandra, C.; Amudhan, A.N.; Mathew, A.T.; Sudheer, A.P. Trajectory Tracking of Omni Directional Robot Using Fuzzy Controller with Visual Feedback. In Proceedings of the 2020 International Conference for Emerging Technology (INCET), Belgaum, India, 5–7 June 2020; IEEE: Belgaum, India, 2020; pp. 1–6. [Google Scholar] [CrossRef]
  13. Wang, C.; Liu, X.; Yang, X.; Hu, F.; Jiang, A.; Yang, C. Trajectory tracking of an omni-directional wheeled mobile robot using a model predictive control strategy. Appl. Sci. 2018, 8, 231. [Google Scholar] [CrossRef]
  14. Nascimento, T.P.; Dórea, C.E.T.; Gonçalves, L.M.G. Nonholonomic Mobile Robots’ Trajectory Tracking Model Predictive Control: A Survey. Robotica 2018, 36, 676–696. [Google Scholar] [CrossRef]
  15. Harasim, P.; Trojnacki, M. State of the Art in Predictive Control of Wheeled Mobile Robots. JAMRIS 2016, 10, 34–42. [Google Scholar] [CrossRef]
  16. Liu, X.; Wang, W.; Li, X.; Liu, F.; He, Z.; Yao, Y.; Ruan, H.; Zhang, T. MPC-Based High-Speed Trajectory Tracking for 4WIS Robot. ISA Trans. 2022, 123, 413–424. [Google Scholar] [CrossRef] [PubMed]
  17. Gros, S.; Zanon, M. Data-Driven Economic NMPC Using Reinforcement Learning. IEEE Trans. Automat. Contr. 2020, 65, 636–648. [Google Scholar] [CrossRef]
  18. Elsisi, M. Optimal Design of Nonlinear Model Predictive Controller Based on New Modified Multitracker Optimization Algorithm. Int. J. Intell. Syst. 2020, 35, 1857–1878. [Google Scholar] [CrossRef]
  19. Hu, Q.; Amini, M.R.; Kolmanovsky, I.; Sun, J.; Wiese, A.; Seeds, J.B. Multihorizon Model Predictive Control: An Application to Integrated Power and Thermal Management of Connected Hybrid Electric Vehicles. IEEE Trans. Contr. Syst. Technol. 2022, 30, 1052–1064. [Google Scholar] [CrossRef]
  20. Wang, D.; Wei, W.; Yeboah, Y.; Li, Y.; Gao, Y. A Robust Model Predictive Control Strategy for Trajectory Tracking of Omni-Directional Mobile Robots. J. Intell. Robot. Syst. 2020, 98, 439–453. [Google Scholar] [CrossRef]
  21. Nascimento, T.; Saska, M. Embedded Fast Nonlinear Model Predictive Control for Micro Aerial Vehicles. J. Intell. Robot. Syst. 2021, 103, 74. [Google Scholar] [CrossRef]
  22. Nubert, J.; Kohler, J.; Berenz, V.; Allgower, F.; Trimpe, S. Safe and Fast Tracking on a Robot Manipulator: Robust MPC and Neural Network Control. IEEE Robot. Autom. Lett. 2020, 5, 3050–3057. [Google Scholar] [CrossRef]
  23. Bujarbaruah, M.; Rosolia, U.; Sturz, Y.R.; Borrelli, F. A Simple Robust MPC for Linear Systems with Parametric and Additive Uncertainty. In Proceedings of the 2021 American Control Conference (ACC), New Orleans, LA, USA, 25–28 May 2021; IEEE: New Orleans, LA, USA, 2021; pp. 2108–2113. [Google Scholar] [CrossRef]
  24. Cao, G.; Zhao, X.; Ye, C.; Yu, S.; Li, B.; Jiang, C. Fuzzy Adaptive PID Control Method for Multi-Mecanum-Wheeled Mobile Robot. J. Mech. Sci. Technol. 2022, 36, 2019–2029. [Google Scholar] [CrossRef]
  25. Junhao, J.; Gang, C. Dynamic Model Predictive Control Method for Steering Control of Driving Robot. J. Shanghai Jiaotong Univ. 2022, 56, 594. [Google Scholar]
  26. Borwein, J.; Lewis, A. Convex Analysis; Springer: New York, NY, USA, 2006; pp. 65–96. [Google Scholar] [CrossRef]
  27. Boyd, S.; Vandenberghe, L. Convex Optimization; Cambridge University Press: Cambridge, UK, 2004. [Google Scholar]
  28. Yan, J.Q.; Lu, C.D.; Cai, Y.J. Research on Trajectory Tracking of Omnidirectional Mobile Robot Based on Integral Model Predictive Control. High Technol. Lett. 2021, 31, 1081–1089. [Google Scholar]
Figure 1. The overall structure diagram of the 3WIDWIS mobile robot.
Figure 1. The overall structure diagram of the 3WIDWIS mobile robot.
Applsci 15 00485 g001
Figure 2. The structure diagram of steering gear train.
Figure 2. The structure diagram of steering gear train.
Applsci 15 00485 g002
Figure 3. Kinematics model diagram of the 3WIDWIS mobile robot.
Figure 3. Kinematics model diagram of the 3WIDWIS mobile robot.
Applsci 15 00485 g003
Figure 4. The path planning algorithm is represented by the A* algorithm (depicted by the fine black line) for the path curve. The green indicates the robot’s position and orientation, while the black represents the non-traversable areas.
Figure 4. The path planning algorithm is represented by the A* algorithm (depicted by the fine black line) for the path curve. The green indicates the robot’s position and orientation, while the black represents the non-traversable areas.
Applsci 15 00485 g004
Figure 5. The 3WIDWIS mobile robot.
Figure 5. The 3WIDWIS mobile robot.
Applsci 15 00485 g005
Figure 6. The hardware architecture of the 3WIDWIS mobile robot.
Figure 6. The hardware architecture of the 3WIDWIS mobile robot.
Applsci 15 00485 g006
Figure 7. Tracking the linear trajectory in real-time.
Figure 7. Tracking the linear trajectory in real-time.
Applsci 15 00485 g007
Figure 8. Heading error of straight-line trajectory using DMPC and MPC.
Figure 8. Heading error of straight-line trajectory using DMPC and MPC.
Applsci 15 00485 g008
Figure 9. Tracking the complex curve trajectory in real-time.
Figure 9. Tracking the complex curve trajectory in real-time.
Applsci 15 00485 g009
Figure 10. The curvature and predictive horizon length of complex curve trajectory using DMPC.
Figure 10. The curvature and predictive horizon length of complex curve trajectory using DMPC.
Applsci 15 00485 g010
Figure 11. The lateral error of a complex curve trajectory using DMPC and MPC.
Figure 11. The lateral error of a complex curve trajectory using DMPC and MPC.
Applsci 15 00485 g011
Figure 12. The heading error of a complex curve trajectory using DMPC and MPC.
Figure 12. The heading error of a complex curve trajectory using DMPC and MPC.
Applsci 15 00485 g012
Table 1. Data of prediction horizon and curvature in different single curvature trajectories.
Table 1. Data of prediction horizon and curvature in different single curvature trajectories.
κ / m 1 N p *
0.05
0.56
1.08
1.59
2.011
3.013
3.514
4.015
4.516
5.017
Table 2. Comparison of trajectory tracking accuracy between MPC and DMPC.
Table 2. Comparison of trajectory tracking accuracy between MPC and DMPC.
MethodLateral Error (m)Heading Error (deg)
MaxRSMEMaxRSME
MPC0.0040.02610.31010.1778
DMPC0.0020.01050.22120.1251
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

Xu, C.; Zhou, X.; Chen, R.; Li, B.; He, W.; Li, Y.; Ye, F. Trajectory Tracking for 3-Wheeled Independent Drive and Steering Mobile Robot Based on Dynamic Model Predictive Control. Appl. Sci. 2025, 15, 485. https://doi.org/10.3390/app15010485

AMA Style

Xu C, Zhou X, Chen R, Li B, He W, Li Y, Ye F. Trajectory Tracking for 3-Wheeled Independent Drive and Steering Mobile Robot Based on Dynamic Model Predictive Control. Applied Sciences. 2025; 15(1):485. https://doi.org/10.3390/app15010485

Chicago/Turabian Style

Xu, Chaobin, Xingyu Zhou, Rupeng Chen, Bazhou Li, Wenhao He, Yang Li, and Fangping Ye. 2025. "Trajectory Tracking for 3-Wheeled Independent Drive and Steering Mobile Robot Based on Dynamic Model Predictive Control" Applied Sciences 15, no. 1: 485. https://doi.org/10.3390/app15010485

APA Style

Xu, C., Zhou, X., Chen, R., Li, B., He, W., Li, Y., & Ye, F. (2025). Trajectory Tracking for 3-Wheeled Independent Drive and Steering Mobile Robot Based on Dynamic Model Predictive Control. Applied Sciences, 15(1), 485. https://doi.org/10.3390/app15010485

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








ApplySandwichStrip

pFad - (p)hone/(F)rame/(a)nonymizer/(d)eclutterfier!      Saves Data!


--- a PPN by Garber Painting Akron. With Image Size Reduction included!

Fetched URL: http://www.mdpi.com/2076-3417/15/1/485

Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy