Abstract
This paper addresses the problem of vision-based line tracking control of unicycle mobile robots. First, a robot-camera model suitable for path following applications is derived. Using a look-ahead approach, a feedback controller is proposed for tracking curved paths on the ground using information from an onboard down-looking camera using distance-only measurements. Stability properties of the closed-loop system are analyzed, and asymptotic stability of the resulting closed-loop control system is proved using Lyapunov stability theory. Simulation and experimental results are presented to illustrate the effectiveness of the proposed control scheme.
Access provided by Autonomous University of Puebla. Download conference paper PDF
Similar content being viewed by others
Keywords
6.1 Introduction
In the last decades, the wheeled mobile robots (WMRs) have been increasingly used in wide range of applications, such as in factories [1], as service robots [2], autonomous vehicles [3], exploration robots [4], for military operations [5], and research [6]. At control level, important results have been established concerning three fundamental motion control tasks, namely point stabilization (the parking problem), trajectory tracking, and path following [7]. In what concerns the path following problem, in contrast of trajectory tracking, the mobile robot has to follow and to converge to a reference path, which is given without temporal specification. The path following control of mobile robot has been intensively studied during the years, and different solutions have been proposed in the literature, such as nonlinear [8] and linear controllers [9]. When designing controllers for path tracking applications, often the curvature of the reference path is considered a priori known, which permits to introduce it directly in the control law, simplifying the design of the controller [10]. In this case, it is also considered that both measurements for the lateral and orientation errors are available for feedback control design [11]. However, depending of the assigned mobile robot guiding point, using look-ahead approach [12], it is possible to use only distance measurements for the lateral offset from the reference line without using data for the orientation error, which considerably simplify the controller design. The advantage of using such approach is considerable in the case, when the mobile robot has to follow a path with unknown curvature and avoids its direct calculation, which involves higher-order derivative computation. In addition, calculation of the orientation error between the mobile robot and the reference path avoided, which considerably simplifies the structure of the controller.
The use of visual information in the feedback loop has been an attractive solution for the motion control of mobile robots and different visual servo algorithms have been developed over the last decades. The control based of visual measurements is termed visual servoing or vision-based control and two main approaches are distinguished, namely position-based visual servoing (PBVS) and image-based visual servoing (IBVS) [13]. In the PBVS approach, three-dimensional scene information is used and the feedback is based on the pose estimation of the observed object with respect to the camera in order to regulate the motion of the onboard camera to a desired pose [14,15,16]. For path following applications, a specific feature is that the error coordinates with respect to the desired path to follow are computed in the task space. In the IBVS approach, the pose estimation is omitted, image features are used as the state in the control, such that the error coordinates are measured in the image, and the control law is directly expressed in the image plane and mapped to actuator commands [17,18,19].
In this paper, we deal with the problem of path tracking control for nonholonomic unicycle WMRs, which use monocular vision guided system for line tracking. The reference path is assumed to be a sequence of circular and/or straight-line segments, where the curvatures of the circular segments are not known. The look-ahead approach [12, 15] used in this paper consists of tracking a reference path with a guiding reference point in front of robot at a given distance ahead from the wheel axle. For this end, first, a robot-camera model of the robot using the look-ahead reference point is derived. A linear controller is designed using lateral error-only measurements without involving values of the path curvature (which is unknown) or the orientation error with respect to the reference path. Based on Lyapunov stability theory, the stability property of the synthesized system is analyzed. Some simulation and experimental results are given, in order to demonstrate the validity of the designed controller.
6.2 Model Development
6.2.1 Robot Kinematic Model
A plane view of a unicycle mobile robot, considered in this paper, which is moving on a horizontal plane, is shown in Fig. 6.1. A monocular camera is placed on the robot pointing downward perpendicular to the ground. For simplicity of exposition, for path following applications, we will use two-dimensional (2D) Cartesian coordinate systems instead 3D systems, where it is possible. With reference to Fig. 6.1, in order to describe the path tracking kinematics, the following coordinate systems are defined: an inertial coordinate system Fxy; a robot coordinate system PxPyP located at the mid-point of the wheel axle with xP axis directed along the longitudinal base of the robot; a robot coordinate system RxRyR attached firmly to the robot at a distance h from the ground and at a distance d ahead from point P, in such way that the xR-axis is aligned with xP-axis of PxPyP; a camera frame CxCyC which center is placed in the optical center of the camera and coincides with the center of the robot frame RxRyR; and a moving virtual reference frame LxLyL associated with the reference line to follow, with a center L assigned in the intersection between the yR-axis of RxRyR and the reference path, such that the xL-axis is tangent to the path and oriented in the direction of motion. The look-ahead point R is defined as a robot guided (reference) point for the line tracking scenario.
Let us denote the coordinates of point P in the fixed frame Fxy as
where \( {}^{F}p_{P} \in R^{2} \), and the orientation of the robot in Fxy as \( \psi \in S^{1} \). The kinematic equations of motion of the unicycle mobile robot under the nonholonomic constraints of pure rolling and nonslipping can be written as follows [12]
where \( \dot{\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{p} }_{P} \) represents the time derivative of \( \overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{p}_{P} \in R^{2} \times S^{1} \), defined as
which is a vector of the posture coordinates of the robot using the reference point P, the transformation matrix \( B_{P} \in R^{3 \times 2} \) is given by
and the vector \( \eta \in \Re^{2} \)
is composed of the robot linear and angular velocities denoted by \( v_{Px} \in \Re \) and \( \omega \in \Re \), respectively.
Denoting with \( {}^{F}p_{R} \in \Re^{2} \) a vector representing the coordinates of point R with respect to Fxy
and with \( {}^{P}d = \left[ {{}^{P}d_{x} \begin{array}{*{20}c} {} \\ \end{array} 0} \right]^{T} \in \Re^{2} \) a vector from point P to point R expressed in the coordinate frame PxPyP, using (6.1) the coordinates of points R and P are related by
where \( R\left( \psi \right) \in SO\left( 2 \right) \) is an orthogonal rotation matrix of angle ψ, (ψ is the orientation angle of the robot with respect to fixed frame Fxy), given by
Differentiating (6.6) with respect to time, one obtains
where \( G = R\left( \psi \right)D \in \Re^{2 \times 2} \) with \( D \in \Re^{2 \times 2} \) given by
\( S\left( {\pi /2} \right) \in SS(2) \) is a skew symmetric matrix and \( {}^{P}\dot{p}_{P} = \left[ {v_{Px} ,v_{Py} } \right]^{T} \in R^{2} \) is a vector of the projections of the velocity of point P relative to the fixed coordinate system Fxy on the axes of the moving robot coordinate system PxPyP.
In order to express the robot kinematic model using the coordinates (6.5) of point R in an inertial frame Fxy, we define a vector of the posture coordinates \( {}^{F}\overset{\lower0.5em\hbox{$\smash{\scriptscriptstyle\frown}$}}{p}_{R} \in R^{2} \times S^{1} \), as follows
Then, using (6.8), one can write
where BR is a block matrix of the form
and the row vector j is given by \( j = \left[ {\begin{array}{*{20}c} 0 & 1 \\ \end{array} } \right] \in \Re^{1 \times 2} \).
The path following geometry considered in this paper is illustrated in Fig. 6.1. It is assumed that the path is a smooth planar curve. The coordinate systems RxRyR and LxLyL are defined to describe the error kinematics during the path tracking process. The moving reference system LxLyL is defined such that the xL-axis is tangent to the path and oriented in the direction of robot motion. The yR-axis of the robot coordinate system RxRyR passes through the reference point L associated with the path to follow.
The coordinates and orientation of the frame LxLyL in the coordinate frame RxRyR can be expressed in the form
where \( e_{\text{pos}} = \left[ {\begin{array}{*{20}c} {x_{e} } & {y_{e} } & {\psi_{e} } \\ \end{array} } \right]^{T} \in \Re^{3} \) is the error posture, xe is the longitudinal error, ye is the lateral error, and ψe is the orientation error; the posture vector \( p_{L} \in \Re^{2} \times S^{1} \) associated with the reference path is defined as
where ψL is the orientation of the coordinate frame LxLyL with respect to the fixed frame Fxy, the posture vector pR is given by (6.8) and the orthogonal matrix \( T \in SO(3) \) is given by
Differentiating (6.10) with respect to time and taking into account the nonholonomic constraints vPy= vLy=0, (vPy and vLy are the projections of the velocities of points R and L on the yR and yL axes, respectively), and using the fact that \( x_{e} (t) = \dot{x}_{e} (t) = 0 \) after some work, the error kinematics for path following applications is obtained in the form
where \( \dot{e} \in \Re^{2} \) represents the time derivative of \( e \in \Re^{2} \) defined as
ζ1(e) and ζ2(e) are C1 vector functions given by
vPx is the velocity of mid-point P of the wheel axle, ω is the angular velocity of the robot considered as control variable (input) of the system, and cr is the curvature of the reference path.
6.2.2 Robot-Camera Model
A monocular camera is placed in front of the mobile robot, where the origin of the camera frame CxCyCzC coincides with the center of the coordinate system RxRyRzR, at distance h from the ground. The optical axis of the camera is perpendicular to the surface of motion, as shown in Fig. 6.2. The focal length of the camera is denoted by f.
The geometric relationships between the onboard camera and a feature point from the reference line are shown in Fig. 6.2. Let us denote the position of a feature point L on the reference line with respect to the camera frame CxCyCzC by \( {}^{C}p_{L} \in \Re^{3} \), as follows
The corresponding pixel coordinates \( {}^{I}p_{L} \) in the pixel coordinate system Iuv fixed to the image plane (Fig. 6.2) are obtained as follows
where \( {}^{C}z_{L} = h \in \Re \), \( T_{\text{int}} \in \Re^{3 \times 3} \) is the intrinsic camera calibration matrix given by
(su, sv) are the camera scaling factors and f is the focal length of the camera.
From (6.15), given the pixel coordinates (uL, vL), one can determine the coordinates of point L in the camera frame CxCyCzC, as follows
On the other hand, given the coordinates \( {}^{C}p_{L} \) of point L in the camera frame CxCyCzC, the coordinates of point L in the robot coordinate frame RxRyRzR are obtained as follows
where the two consecutive rotation matrices \( R_{{x_{C} ,\pi }}^{{}} \in SO(3) \) and \( R_{{z_{C} ,\pi /2}}^{{}} \in SO(3) \) are given by
The lateral error ye is calculated from the image based on the pixel coordinates in the image plane of the image feature point LI (Fig. 6.3), corresponding to the feature point L from the reference line on the ground. Knowing the camera intrinsic parameters and the height h of the camera from the ground, the coordinates of a feature point L belonging to the reference line in the robot reference system RxRyRzR can be recovered from its pixel coordinates in the image plane. This error distance is obtained as a difference between the image plane coordinates of the principal point C and the image point LI, respectively, and is a function of the intrinsic camera parameters and the known distance h from the camera to the ground.
6.3 Feedback Control Design and Stability Analysis
6.3.1 Circular Line Tracking
Assuming that the reference path is a sequence of circular segments or/and straight lines, and robot velocity vPx is constant and positive (forward robot motion), the path tracking problem consists of finding a feedback control law for the system (6.12) with control input ω, such that the state vector e = [ye, ψe]T tends to es = [yes, ψes]T as t → ∞, where yes and ψes have constant values.
The following feedback control law is proposed
where k is a positive constant and vPx, (vPx= cte >0), is the robot speed.
Applying (6.18) to (6.12), the resulting nonlinear closed-loop system has the form
where the vector function ηc given by
is continuously differentiable.
The equilibrium point es of system (6.19) is at
The stability of the equilibrium point (6.20) for the nonlinear system (6.19) is analyzed by investigating the stability of the linearized system using Lyapunov stability theory [20].
The linearization of the nonlinear system (6.19) at the equilibrium point (6.20) has the form
where the vector \( \Delta e \in \Re^{2} \) is given by
\( M_{c} \in \Re^{2 \times 2} \) is the Jacobian matrix of ηc, (vPx= cte >0) in the form
with
To analyze the stability of linear system (6.21), we test the eigenvalues λi, (i =1, 2) of matrix Mc. The characteristic equation of matrix Mc takes the form
In order that the squired Eq. (6.24) does not have any roots with positive real part, it is necessary and sufficient that all its coefficients be of the same sign, which implies that
and
To be more concrete, consider the case when the curvature of the reference path cr = cte > 0 (analogous results can be obtained when cr = cte < 0), and also the following inequality holds
irrespective of the sign of ye.
In order to prove that inequality (6.25) holds, the expression for yes from the first equation of (6.20) is substituted into (6.25). Using (6.23), and taking into account that
where
after some work, the following inequality is obtained
which means that the inequality (6.25) holds.
In order to prove that inequality (6.26) holds, using the expression for det(Mc) from the last coefficient of (6.24), and taking into account that s >0, one has to prove that
Using the first equation from (6.20) for yes, and the expressions for m12 and m21 given in (6.23), after some work, the following inequality is obtained
which means that the inequality (6.24) holds.
Based on (6.30) and (6.32), it follows that Reλi < 0, (i =1, 2). Application of the Lyapunov’s indirect method [13] indicates that the equilibrium point [yes, ψes]T is locally asymptotically stable point for the nonlinear system (6.19).
6.3.2 Straight-Line Tracking
In particular, in the case of straight line following (cr=0 in (6.12)), and applying the feedback control law given by (6.18), the resulting time-invariant closed-loop system (6.19), (vPx = cte > 0), has the form
where the vector e is given by (6.13) and the vector function ηc is in the form
The origin (0, 0) becomes an equilibrium point for the nonlinear system (6.33). After linearizing the system (6.33) around the origin, is obtained
where the matrix \( M_{s} \in \Re^{2 \times 2} \) has the form
A Lyapunov function for the linear system (6.34) is found by taking a positive definite matrix \( Q \in R^{2 \times 2} \) of the form (vPx= cte > 0)
and solving for \( P \in \Re^{2 \times 2} \) the Lyapunov equation
The unique solution of the matrix Eq. (6.37) for P is obtained as follows
The symmetric matrix P is positive definite since its leading principal minors are positive (k = cte >0; \( {}^{P}d_{x} \) = cte >0)
Hence, Mc is stability matrix (i.e., Reλi < 0 for the eigenvalues of Mc) for the system (6.34), [20]. Since the robot velocity is assumed to be constant and strictly positive, it follows that using control (6.18) local asymptotic stability of the nonlinear system (6.33) is achieved when the control (6.18) is applied.
6.4 Simulation and Experimental Results
Numerical simulation tests using MATLAB and experiments are carried out in order to validate the proposed path tracking control. The look-ahead distance for the robot reference point R (Fig. 6.1) was chosen to be \( {}^{P}d_{x} \) = 0.3 m. The forward robot velocity was chosen to be vPx=0.3 m/s and the controller gain in feedback control given by (6.18) was ky=10.
For the first simulation, a circular reference path of radius 1 m was assigned. In the first test in circular path following, the initial conditions were chosen to be \( e = [\begin{array}{*{20}c} {y_{e} (0)} & {\psi_{e} (0)} \\ \end{array} ]^{T} = [\begin{array}{*{20}c} { - 0.3} & { - 0.3} \\ \end{array} ]^{T} \). The path drown by the robot guide point R and evolution in time of the path error coordinates are depicted, respectively, in Fig. 6.4a, b.
For the second simulation test in circular path following, the initial conditions were \( e = [\begin{array}{*{20}c} {y_{e} (0)} & {\psi_{e} (0)} \\ \end{array} ]^{T} = [\begin{array}{*{20}c} {0.3} & {0.3} \\ \end{array} ]^{T} \). The path drown by the robot guide point R and evolution in time of the path error coordinates is depicted in Fig. 6.4c, d, respectively. As seen from Fig. 6.4b, d, the error coordinates ye(t) and ψe(t) asymptotically tend to the steady-state values given by (6.20), which is in conformity with the stability analysis presented in Sect. 6.3. The steady-state lateral error yes in the both cases is equal to 0.095 m.
For the straight-line path tracking simulation test, the initial conditions were chosen to be \( e = [\begin{array}{*{20}c} {y_{e} (0)} & {\psi_{e} (0)} \\ \end{array} ]^{T} = [\begin{array}{*{20}c} {0.25} & {0.1} \\ \end{array} ]^{T} \). The path drown by the robot guide point R and evolution in time of the path error coordinates are depicted, respectively, in Fig. 6.5a, b, respectively. The results from the simulation confirmed the analytical result obtained in the previous section for straight-line tracking, that the error coordinates ye and ψe(t) asymptotically tend to zero.
Experiments were carried out for tracking a circular and straight-line path using a differential-drive mobile robot Pioneer-3DX equipped with an onboard low cost camera (640 × 480 pixels). For the experiments, the velocity of the robot was set to vPx=0.3 m/s. As seen from Fig. 6.6, the robot was able to follow a circular path with small steady-state lateral error according to (6.20) and without error for straight-line tracking (Fig. 6.7).
6.5 Conclusion
In this paper, a vision-based line following controller for unicycle mobile robots was presented. Using a look-ahead approach, a simple and effective feedback control, which achieves local asymptotic stability of the nonlinear closed-loop system for a circular path with unknown curvature, as well and a straight-line path, was designed and analyzed using Lyapunov stability theory. Simulation and experimental results confirm the validity of the designed vision-based control scheme to perform curved path following in clutter environments with a quite good accuracy.
References
Liaqat, A., Hutabarat, W., Tiwari, D., Tinkler, L.: Autonomous mobile robots in manufacturing: highway code development, simulation, and testing. Int. J. Adv. Manuf. Technol. 104, 4617–4628 (2019)
Sinyukov, D., Padir, T.: Adaptive motion control for a differentially driven semi-autonomous wheelchair platform. In: International Conference on Advanced Robotics, pp. 288–294. IEEE, Istanbul, Turkey (2015)
Petrov, P., Nashashibi, F.: Planning and nonlinear adaptive control for an automated overtaking maneuver. In: 14th International IEEE Conference on Intelligent Transportation Systems, pp. 662–667. IEEE, Washington, DC, USA (2011)
Palacios, A., Sanchez, A., Bedolla, A., Cordero, J.: The random exploration graph for optimal exploration of unknown environments. Int. J. Adv. Rob. Syst. 14(1), 1–11 (2017)
Rahmat, M., Hudha, K., Idris, A., Amer, N.: Sliding mode control of target tracking system for two degrees of freedom gun turret model. Adv. Military Technol. 11(1), 13–28 (2016)
Calvo, C., Villacorta-Atienza, J., Mironov, V., Gallego, V., Makarov, V.: Waves in isotropic totalistic cellular automata: application to real-time robot navigation. Adv. Complex Syst. 19(4), 1–18 (2016)
Petrov, P., Nashashibi, F.: Saturated feedback control for an automated parallel parking assist system. In: 13th International Conference on Control Automation Robotics and Vision, pp. 577–582. IEEE, Singapore (2014)
Ibrahim, F., Abouelsoud, A., Elbab, A., Ogata, T.: Path following algorithm for skid-steering mobile robot based on adaptive discontinuous posture control. Adv. Robot. 33(9), 439–453 (2019)
Emam, M., Fakharian, A.: Solving path following problem for car-like robot in the presence of sliding effect via LMI formulation. J. Comput. Rob. 10(2), 11–22 (2017)
De Luca, A., Oriolo, G., Vendittelli, M.: Control of wheeled mobile robots: an experimental overview. In: Nicosia, S., Siciliano, B., Bicchi, A., Valigi, P. (eds.), LNCIS, vol. 270, pp. 181–226. Springer, Berlin, Heidelberg (2001)
Plaskonka, J.: Different kinematic path following controllers for a wheeled mobile robot of (2, 0) type. J. Intell. Rob. Syst. 77, 481–498 (2015)
Petrov, P., Kralov, I.: A look-ahead approach to mobile robot path tracking based on distance-only measurements. AIP Conf. Proc. 2172, 110005 (2019)
Hutchinson, S., Hager, G., Corke, P.: A tutorial on visual servo control. IEEE Trans. Rob. Autom. 12(6), 651–670 (1996)
Cherubini, A., Chaumette, F. Oriolo, G.: A position-based visual servoing scheme for following paths with nonholonomic mobile robots. In: IEEE/RSJ International Conference on Intelligent Robots and Systems, pp. 1648–1654. IEEE, Nice, France (2008)
Petrov, P., Georgieva, V.: Vision-based line tracking control for nonholonomic differential-drive mobile robots. In: 9th National Conference with International Participation, ELECTRONICA 2018. IEEE, Sofia, Bulgaria (2018)
Kim, S., Oh, S.: Hybrid position and image based visual servoing for mobile robots. J. Intell. Fuzzy Syst. 18, 73–82 (2007)
Corke, P.: Mobile robot navigation as a planar visual servoing problem. In: Jarvis, R., Zelinsky, A. (eds.), Robotics Research, STAR vol. 6, pp. 361–372. Springer, Berlin Heidelberg (2003)
Kountchev, R., Mironov, R., Kountcheva, R.: Hierarchical cubical tensor decomposition through low complexity orthogonal transforms. Symmetry 12(5), 1–17 (2020)
Mariottini, G., Oriolo, G., Prattichizzo, D.: Image-based visual servoing for nonholonomic mobile robots using epipolar geometry. IEEE Trans. Rob. 23(1), 87–100 (2007)
Khalil, H.: Nonlinear systems, 3rd edn. Pearson, USA (2002)
Acknowledgements
This work was supported by the National Science Fund at the Ministry of Education and Science, Republic of Bulgaria, within the project KP-06-H27/16 “Development of Efficient Methods and Algorithms for Tensor-based Processing and Analysis of Multidimensional Images with Application in Interdisciplinary Areas.”
Author information
Authors and Affiliations
Corresponding author
Editor information
Editors and Affiliations
Rights and permissions
Copyright information
© 2021 The Author(s), under exclusive license to Springer Nature Singapore Pte Ltd.
About this paper
Cite this paper
Petrov, P., Georgieva, V. (2021). Vision-Based Line Tracking Control and Stability Analysis of Unicycle Mobile Robots. In: Kountchev, R., Mironov, R., Li, S. (eds) New Approaches for Multidimensional Signal Processing. Smart Innovation, Systems and Technologies, vol 216. Springer, Singapore. https://doi.org/10.1007/978-981-33-4676-5_6
Download citation
DOI: https://doi.org/10.1007/978-981-33-4676-5_6
Published:
Publisher Name: Springer, Singapore
Print ISBN: 978-981-33-4675-8
Online ISBN: 978-981-33-4676-5
eBook Packages: EngineeringEngineering (R0)