Next Article in Journal
Design of a Herringbone-Grooved Bearing for Application in an Electrically Driven Air Compressor
Next Article in Special Issue
Orientation Modeling Using Quaternions and Rational Trigonometry
Previous Article in Journal
A Study on Gear Defect Detection via Frequency Analysis Based on DNN
Previous Article in Special Issue
Flatness-Based Active Disturbance Rejection Control for a PVTOL Aircraft System with an Inverted Pendular Load
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Navigation of a Differential Wheeled Robot Based on a Type-2 Fuzzy Inference Tree

by
Dante Mújica-Vargas
1,*,
Viridiana Vela-Rincón
1,
Antonio Luna-Álvarez
1,
Arturo Rendón-Castro
1,
Manuel Matuz-Cruz
2 and
José Rubio
3
1
Department of Computer Science, Tecnológico Nacional de México/CENIDET, Interior Internado Palmira S/N, Palmira, Cuernavaca 62490, Mexico
2
Departamento de Sistemas Computacionales, Tecnológico Nacional de México/ITTapachula, Tapachula Chiapas 30700, Mexico
3
Sección de Estudios de Posgrado e Investigación, ESIME Azcapotzalco, Instituto Politécnico Nacional, Av. de las Granjas No. 682, Col. Santa Catarina, Ciudad de México 02250, Mexico
*
Author to whom correspondence should be addressed.
Submission received: 30 June 2022 / Revised: 2 August 2022 / Accepted: 3 August 2022 / Published: 5 August 2022
(This article belongs to the Special Issue Control of Robotic Systems)

Abstract

:
This paper presents a type-2 fuzzy inference tree designed for a differential wheeled mobile robot that navigates in indoor environments. The proposal consists of a controller designed for obstacle avoidance, a controller for path recovery and goal reaching, and a third controller for the real-time selection of behaviors. The system takes as inputs the information provided for a 2D laser range scanner, i.e., the distance of nearby objects to the robot, as well as the robot position in space, calculated from mechanical odometry. The real performance is evaluated through metrics such as clearance, path smoothness, path length, travel time and success rate. The experimental results allow us to demonstrate an appropriate performance of our proposal for the navigation task, with a higher efficiency than the reference methods taken from the state of the art.

1. Introduction

Robot navigation is the problem of guiding a robot toward a goal [1]. The autonomous navigation is conditioned to the planning of motions, i.e., the interrelationship between tasks, such as the environment perception, path planning, and path tracking, among others. Thus, it might be said that the planning of motions plays a key role for mobile robotic systems. In mobile robotics, the principle behind the motion planning problem is to guide a robot through an environment and interact with objects or tools, avoiding obstacles and taking into account any restrictions, such as those of mobility and energy [2]. Motion planning for mobile robots is one of the most challenging problems; over time, its different inherent subproblems have been expanded by adding variables such as dynamic obstacles, complex environments, dead reckoning, linear and angular velocities control, holonomic and nonholonomic constraints, energy, fault tolerance, algorithms runtime and so on.
Motion planning and its inherent problems have been a researched area for several years. The state of the art suggests different investigation lines; just to name a few, the following may be mentioned. For the shortest path planning, there are planners, such as Dijkstra [3], A* [4], and Theta* [5], and based on them, there are so important proposals [6,7,8,9,10,11,12,13]. For path planning, there exist also developments based on optimal control theory [14,15]. For motion planning are highlighted such methods as Hybrid A* (HybridAStar) [16], rapidly exploring random tree (RRT) [17], bidirectional rapidly exploring random tree (BiRRT) [18] and probabilistic road map (PRM) [19]. In terms of path tracking, i.e., where a reference trajectory is known beforehand, there are approaches based on predictive control [20], based on fuzzy theory [21], and based on classic control [22]. There is also a significant contribution related with the obstacles avoidance and the reaching goal time reduction; the broad range includes the A* algorithm [23,24], neural networks [25], genetic algorithms [26,27], fuzzy logic [28], particle swarm optimization [29], and ant colony optimization [30], among others [31,32].
There is an abundance of literature on this subject to cover in the current study; notwithstanding, it is necessary to mention merged approaches. Some developments may be cited, for instance, in [33], an ant colony algorithm was proposed using an evaluation function of the A* algorithm to accelerate the algorithm convergence rate. It was designed for the path planning. In this regard, two ant colony algorithms were executed independently and successively in [34]. On the other hand, ant colony was fused with fuzzy logic in [35]. In [36], the shortest path problem was addressed with a PRM in cooperation with a fuzzy controller; this last helped in having smooth curves by adjusting the turning angles and correcting the position and orientation of the robot. A knowledge-based neural fuzzy controller was introduced in [37], and was evaluated using a PIONEER 3-DX platform for navigation and obstacle avoidance tasks. Finally, there are a few contributions where the technology and new computational paradigms are considered. By this way, in [38], the robot operating system (ROS) and sensors such as 2D LiDAR and RGB-D, were used to perform the navigation task with dynamic obstacle avoidance capability. In [23], the pure pursuit algorithm was improved by considering the 2D LiDAR point-cloud features with a deep convolutional network. LiDAR sensors have also been combined with deep convolutional neural network models to navigation control for wheeled mobile robots, as described in [39].
In this study, we concentrate on the motion planning, by providing autonomy to a differential wheeled robot. That is to say, the mobile robot navigates and interacts with objects within the environment, and intrinsically it is able to know where it is located and where it will go. The contributions of this study are summarized as follows:
  • A type-2 fuzzy inference tree is proposed as real-time motion planning in the mobile robot navigation problem.
  • Type-2 fuzzy theory is the theoretical support of the current system, which makes it different from common fuzzy controllers used in mobile robotics, where type-1 fuzzy theory is used.
  • The tree scheme is suggested as a solution to reduce the computational complexity, by the delegation of tasks, specifically, obstacle avoidance, path recovering, and goal reaching, as well as behavior coordination.
  • The proposal is fully functional on physical robotic platforms, in contrast with many state-of-the-art approaches that are computational simulations.
  • The performance of the proposed system was evaluated on a real environment with a smooth floor and rough surfaces.
The rest of this paper is organized as follows. In Section 2, the system composition is described in detail, with a special emphasis on the proposed type-2 fuzzy inference tree and its mathematical background. Experimental results and a comparative analysis with other current methods in the literature are presented in Section 3. The concluding section gives a synopsis of the principal results and recommendations for future work.

2. Materials and Methods

2.1. System Composition

The system used in this study is shown in Figure 1. It consists of a Roomba 620 mobile robot with two differential drive wheels fitted with incremental wheel encoders; its linear v and angular w velocity limits comprise 0.5 v 0.5 (m/s) and 4.25 w 4.25 (rad/s). It also includes a 360 2D laser range scanner RPLIDAR-A3 with a maximum ranging distance of 25 m, sampling frequency of 20 Hz and angular resolution of 0.25 . These devices are controlled by a local ARM CPU set up with ROS Melodic; in particular, it develops three tasks. The first activity is setting up both linear velocity v and steering w, as well as taking measures of angular velocities for right and left wheels ( w r and w l , respectively). This information is used to compute the robot position P = { x , y , θ } over time, by means of odometry kinematics. The second task implies detecting nearby objects; to this end, distance r and angle ϕ readings are taken, using a laser scanner. The sensor is able to acquire 360/0.25 = 1440 measures, every 1 / 20 = 0.05 seconds; for simplicity, the information is represented in matrix form as S = { r i , ϕ i } . The latest process involves transmitting P and S arrays over Wi-Fi to the remote CPU, just as receiving velocity and steering commands. On the remote desktop computer, provided with Matlab, Fuzzy Logic and ROS toolboxes, the proposed control system is executed in real time.

2.2. Laser Range Scanner Measures

The LIDAR sensor scans the environment in an omnidirectional way, with an angle resolution of 0.25 , plus a 25 m maximum operating range. For appropriate sensor operation within this framework research, the next constraints are set as: (a) Just 180 frontal coverage is required. (b) A detection range between 0.15 m and 0.55 m is considered since the robot navigates in indoor environments. In 180 coverage, it is possible to acquire 180/0.25 = 720 measures; these readings cannot be considered inputs to the fuzzy tree system. To address this issue, it is suggested to work with 30 regions, as shown in Figure 2. For simplicity, they are labeled as Right-Down (RD), Right-Up (RU), Right-Front (RF), Left-Front (LF), Left-Up (LU) and Left-Down (LD).
For every zone, 30/0.25 = 120 measures (m) may be acquired. Readings with the minimum values are of special interest, since they allow locating the closest objects. They are computed as follows:
RD m i n = min ( m 0.0 , m 0.25 , , m 30.0 ) ,
RU m i n = min ( m 30.25 , m 30.5 , , m 60.0 ) ,
RF m i n = min ( m 60.25 , m 60.5 , , m 90.0 ) ,
LF m i n = min ( m 90.25 , m 90.5 , , m 120.0 ) ,
LU m i n = min ( m 120.25 , m 120.5 , , m 150.0 ) ,
LD m i n = min ( m 150.25 , m 150.5 , , m 180.0 ) .

2.3. Odometry

The simplest and commonly used approach for robot localization is based on mechanical odometry; it uses information from wheel encoders to estimate all changes in position over time (see Figure 3).
To understand the differential robot motion, it is necessary to compute how much every wheel contributes to robot velocity, by considering the following expressions [40]:
v r = 2 π r · n r ( t ) n r ( t Δ t ) N Δ t ,
v l = 2 π r · n l ( t ) n l ( t Δ t ) N Δ t ,
where v r and v l are the right and left wheel velocities, respectively, r is the wheel radius, N is the encoder ticks number for one full wheel revolution, n r and n l are encoder ticks of the right and left wheel at time t, respectively, and n r ( t Δ t ) and n l ( t Δ t ) are the same quantities at the previous sampling time. Expressions (7) and (8) let us compute both linear v and angular w velocities of the robot as
v = v r + v l 2 ,
w = v r v l l ,
where l stands for the distance between the wheels. The robot position ( x ( t ) and y ( t ) ), as well as the orientation ( θ ( t ) ) can then be estimated with discrete numerical integration (e.g., Euler) as
x ( t ) = x ( t Δ t ) + v cos ( θ ( t ) ) Δ t ,
y ( t ) = y ( t Δ t ) + v sin ( θ ( t ) ) Δ t ,
θ ( t ) = θ ( t Δ t ) + w Δ t .
In particular for Roomba 620 robot, the counts per revolution are N = 508.8 , the wheel radius is r = 0.036 (m) and the wheel baseline is l = 0.235 (m).

2.4. Proposed Type-2 Fuzzy Inference Tree

The type-2 fuzzy inference tree proposed in this study is shown in Figure 4. In brief, the behaviors controller takes all inputs to analyze the environment and the robot position with respect to the goal. If there are obstacles near the robot, the controller selects the obstacle avoidance behavior; otherwise, the goal reaching behavior is chosen.
Figure 5 depicts the type-2 fuzzy sets for all inputs, by convention they can be considered two subsets. RD, RU, RF, LF, LU and LD variables are the first subset; this allows us to quantify the obstacles proximity during the navigation. Error and distance variables are the second subset; it enables us to measure the error angle with respect to goal and the distance to reach the target. The operating range for each variable was established considering that the robot navigates only in indoor environments; however, it can be extended to outdoor environments.
All variables of the first subset are modeled by three Gaussian fuzzy sets, denoted as Near (N), Medium (M) and Far (F). For the second one, they are modeled independently, i.e., the error variable is modeled with five trapezoidal fuzzy sets named Negative (N), Small Negative (SN), Zero (Z), Small Positive (SP) and Positive (P). By contrast, the distance variable is described with three trapezoidal fuzzy sets, so-called Near (N), Medium (M) and Far (F).
Figure 6 depicts the output variables; to achieve a better understanding, also consult Figure 4. At first instance, the behaviors output is modeled by two sets titled GoalReaching and ObsAvoidance; this output develops a binary classification or a switching between behaviors. On the other hand, both obstacle avoidance and goal reaching controllers have the same outputs, which allow to adjust the steering and velocity. For this purpose, the steering output is modeled by five trapezoidal fuzzy sets labeled as Right (R), Right Front (RF), Front (F), Left Front (LF) and Left (L). This variable is the angular velocity; in this study it is considered a range of 1 w 1 radians per second. Finally, Velocity variable stands for the linear velocity, it is considered 0 v 0.2 m per second. The output is modeled by three sets, Zero (Z), Small Positive (SP) and Positive (P). Negative velocities are not considered, since backward movements are not required.

2.5. Mathematical Support of the Proposal

The current proposal consists of three multiple-input multiple-output type-2 fuzzy controllers. In order to simplify its mathematical support, it can be assumed that each system can be seen as a combination of multiple-input single-output type-2 fuzzy controllers. A conventional type-2 fuzzy system with a type-reduction + defuzzification contains five components which are the fuzzifier, rule base, fuzzy inference engine, type-reducer and defuzzifier [41]. To describe these components, the following conceptualization can be standardized and applicable for all three controllers.

2.5.1. Fuzzifier

Fuzzifier takes a crisp input vector with n samples provided by the sensors ( x 1 , , x n ) T X 1 × × X n X and maps it into type-2 fuzzy sets. The literature suggests type-2 singleton, type-1 non-singleton and type-2 non-singleton fuzzifiers [41,42]. In this study, type-2 singleton was chosen since it is fast to compute and thus suitable for the robot real-time operation. Given a type-2 fuzzy set X ˜ i , a type-2 singleton fuzzifier is one for which μ X ˜ i ( x i | x i ) = 1 / 1 when x i = x i and μ X ˜ i ( x i | x i ) = 1 / 0 if x i x i .

2.5.2. Rule Base

In [41], it was stated that the rules for a type-2 fuzzy controller were similar as type-1 fuzzy controller, provided that the type-1 fuzzy sets were replaced by type-2 fuzzy sets. Therefore, the structure of the k-th rule for a multiple-input single-output type-2 fuzzy controller based on Mamdani inference is given as
R ˜ k : IF x 1 is F ˜ 1 k a n d a n d x n is F ˜ n k THEN y is G ˜ k ,
where F ˜ 1 k { X ˜ 1 j } j = 1 Q 1 , , F ˜ n k { X ˜ n j } j = 1 Q n stand for the Q i linguistic terms that modeled each i-th input. Likewise, G ˜ k { Y ˜ j } j = 1 Q describes the linguistic terms that model the output.

2.5.3. Fuzzy Inference Engine

The inference engine combines rules and makes a mapping from input type-2 sets to output type-2 sets [41]. For this purpose, a set of 1 k M rules having n inputs x 1 X 1 , , x n X n , as well as an output y Y are taken into account, then the transformation process is formalized as
R ˜ k : F ˜ 1 k × × F ˜ n k G ˜ k = A ˜ k G ˜ k ,
where A ˜ k = F ˜ 1 k × × F ˜ n k . R ˜ k can be described by the membership function μ R ˜ k ( x , y ) = μ R ˜ k ( x 1 , , x n , y ) , which implies that:
μ R ˜ k ( x , y ) = μ A ˜ k G ˜ k ( x , y ) ,
x stands for a condensed representation of the n inputs. The expansion of (16) is given by
μ A ˜ k G ˜ k ( x , y ) = μ ( F ˜ 1 k × × F ˜ n k ) ( x ) G ˜ k = i = 1 n μ F ˜ i k ( x i ) μ G ˜ k ( y ) ,
⊓ denotes the intersection of the type-2 fuzzy sets. Moreover, the n-dimensional input to the rule set is given by type-2 fuzzy set A ˜ x whose membership function is stated as
μ A ˜ x ( x ) = μ X ˜ 1 ( x 1 | x 1 ) μ X ˜ n ( x n | x n ) = i = 1 n μ X ˜ i ( x i | x i ) .
To establish a direct connection between the input and output, it should be kept in mind that rules determine which sets are triggered on the output. This is formalized by
μ B ˜ k ( y , x ) = x X μ A ˜ x ( x ) μ R ˜ k ( x , y ) .
If (17) and (18) are substituted into (19), an input–output relation can be expressed as
μ B ˜ k ( y , x ) = i = 1 n x i X i μ X ˜ i ( x i | x i ) μ F ˜ i k ( x i ) μ G ˜ k ( y ) .
The bracket term is so-called a firing set [41], it is denoted as F k ( x ) , and it allows to simplify (20) in the following way:
μ B ˜ k ( y , x ) = F k ( x ) μ G ˜ k ( y ) ,
μ B ˜ k ( y , x ) stands for the membership function for a fired rule output set. For a type-2 Mamdani fuzzy inference system, the singleton fuzzification [41] is rewritten as
μ B ˜ k ( y , x ) = 1 / f ̲ k ( x ) , f ¯ k ( x ) μ G ˜ k ( y ) ,
where f ̲ k ( x ) and f ¯ k ( x ) depict the lower and upper membership degrees of the footprint of uncertainty, given by
f ̲ k ( x ) = μ ̲ F ˜ 1 k ( x 1 ) 🟉 μ ̲ F ˜ 2 k ( x 2 ) 🟉 🟉 μ ̲ F ˜ n k ( x n ) ,
f ¯ k ( x ) = μ ¯ F ˜ 1 k ( x 1 ) 🟉 μ ¯ F ˜ 2 k ( x 2 ) 🟉 🟉 μ ¯ F ˜ n k ( x n ) ,
where 🟉 is used to denote the minimum or product implication method.

2.5.4. Type-Reduction

When a type-2 fuzzy inference system is used in a real-world application, the issue of the computational cost and complexity become non-trivial [41]. In this regard, a type-reduction process can be performed on μ B ˜ k ( y , x ) in order compute an output. Output region Z B ˜ requires the entire footprint of uncertainty of B ˜ or a sampled version of it as its starting point, and is
Z B ˜ = 1 / [ z l ( B ˜ ) , z r ( B ˜ ) ] ,
where z l ( B ˜ ) and z r ( B ˜ ) are the left and right transition of the membership function that defines the output region. They can be computed by means of
z l ( B ˜ ) = l = 1 L y l μ ¯ B ˜ ( y l | x ) + l = L + 1 N y l μ ̲ B ˜ ( y l | x ) l = 1 L μ ¯ B ˜ ( y l | x ) + l = L + 1 N μ ̲ B ˜ ( y l | x ) ,
z r ( B ˜ ) = l = 1 R y l μ ¯ B ˜ ( y l | x ) + l = R + 1 N y l μ ̲ B ˜ ( y l | x ) l = 1 L μ ¯ B ˜ ( y l | x ) + l = R + 1 N μ ̲ B ˜ ( y l | x ) .
If the centroid approach is considered, a continuous output region is generated from the activated rules; therefore, sample values of μ ̲ B ˜ ( y l | x ) and μ ¯ B ˜ ( y l | x ) can be computed. In this study, the enhanced Karnik and Mendel (EKM) algorithm [41] was chosen, largely because it has a better initialization, which reduces the number of iterations, as well as the fact that it has a subtle computing technique, which is used to reduce the computational cost of each algorithm iteration, among other aspects.

2.5.5. Defuzzification

The last process in a fuzzy system implies the defuzzification. Taking into account [ z l ( B ˜ ) , z r ( B ˜ ) ] , the defuzzified output y Z ( x ) for a type-2 Mamdani fuzzy inference system may be computed via
y Z ( x ) = z l ( B ˜ ) + z r ( B ˜ ) 2 .

3. Experimental Results

To assess and confirm the current proposal performance, two experiments were carried out on an indoor environment, with no dynamic objects. For the first trial, an obstacle-free environment was considered, while for the second one, some objects were included to make it difficult to navigate and reach the goal. As seen in Figure 7, the hallways of the Computer Science Department building of CENIDET (National Center of Research and Technological Development, Spanish acronym) constitute our experimentation environment.
Figure 8 depicts sketches of the real dimensions, as well as an occupancy grid map built from lidar scans and poses collected by the robot through a remotely controlled navigation. All unnecessary objects were removed from the building structure to have a completely obstacle-free map.
For the purpose of having a performance benchmark, the current proposal and some well-known methods from the literature were evaluated to perform the 2D path planning and avoiding obstacles for a differential drive robot. In particular, the comparative methods were HybridAStar [16], RRT [17], BiRRT [18] and PRM [19]. All of them are available in Matlab; therefore, they were not programmed manually, not to impair their performance. In this regard, these are easily workable with a robotic platform in a physical way. It is necessary to clarify that although novel techniques for trajectory tracking have recently been presented in the literature, they cannot be used in the context of this research work. The aim is not just to follow a path, since the avoidance of obstacles and the recovery of the trajectory must be done, or failing that, new trajectories must be calculated and followed during navigation.
For an objective comparison, some performance metrics [2,43] were taken as a reference, such as clearance, path smoothness, path length, travel time and success rate.
  • Clearance: this metric is related to the distance from the trajectory points to the closest obstacle, and it is defined as
    ζ = 1 n i = 1 n δ i = 1 n i = 1 n ( x i x c l o s e O b s t ) 2 + ( y i y c l o s e O b s t ) 2 ,
    where δ i represents the Euclidean distance from the i-point of the path to the closest obstacle and n is the number of points of the path. A higher clearance value indicates a lower risk of collision.
  • Path smoothness: the smoothness of a path refers to the amplitude of the angles that are described while the robot follows the trajectory
    κ = 1 n i = 2 n α i = 1 n i = 2 n arctan y i + 1 y i x i + 1 x i arctan y i y i 1 x i x i 1 ,
    where α i stands for the angle between two consecutive segments of a path with n segments. A lower smoothness value indicates smoother path.
  • Path length: is defined as the sum of the distances from one way point to the next one in the planner state space.
    = i = 1 n 1 ( x i x i + 1 ) 2 + ( y i y i + 1 ) 2 .
  • Travel time: is the time span that the robot travels the entire path from the start to the goal.
  • Success rate: is equal to the percentage of times an algorithm is able to find a valid solution.
For both experiments, each planner was run 10 times since some comparative algorithms have a random nature. Thus, the quantitative results summarized in next subsections imply average and standard deviation values, while to illustrate the paths, the best one was selected for each method. An aspect to bear in mind is that for comparative algorithms, linear and angular velocities are fixed to v = 0.5 (m/s) and w = 1 , 1 (rad/s), whilst for our proposal, they are adjustable.

3.1. Experiment 1: Navigation on an Obstacles-Free Environment

The differential robotic platform used in this study does not have inertial or global positioning sensors; in consequence, its position in the navigation environment is calculated through incremental mechanical encoders. It is well known that dead reckoning based on these sensors is subject to cumulative error. To deal with this inherent situation, the desired path is defined through a waypoint set. In this experiment, the start and goal points are
S t a r t = { [ 13.0 , 4.75 , π ] } ,
G o a l = { [ 16.5 , 17.5 , 0 ] } ,
while the path consists of next waypoints:
P a t h = { [ 13.0 , 4.75 , π ] ; [ 5.25 , 8.3 , π / 2 ] ; [ 5.25 , 15.5 , π / 2 ] ; [ 10.0 , 17.5 , 0 ] ; [ 16.5 , 17.5 , 0 ] } T .
Figure 9 shows the paths generated by all evaluated algorithms during the navigation from start to goal. It can be seen that, all of them were able to reach the goal; however, it should be stressed that our proposal made the shortest route with a remarkable smoothness. These two latter aspects are of particular relevance in the mobile robotics context since they represent a lower energy consumption.
Table 1 supports quantitatively previous subjective analyzing, by summarizing the average and standard deviation values. In terms of the clearance metric, the introduced approach allowed the robot to avoid the corners of the environment at a distance of 0.503 m, that is, the collision risk is lower compared to the other algorithms. For path smoothness, the current proposal achieved the lowest value, i.e., 0.236 , while the RRT and PRM algorithms obtained the highest values; in other words, their paths were rougher. The BiRRT algorithm can be highlighted since it made the longest trip to reach the goal, but in the navigation task it is expected to reach the goal with less displacement. Travel time reveals that PRM, BiRRT and RRT required a shorter time than the current proposal. In addition to the aforementioned aspects, for 10 tests, all algorithms allowed the robot to reach the goal.
In general, it can be seen that in a navigation environment free of obstacles, all the methods allowed a successful navigation of the robot. However, in real work environments, there are always obstacles.

3.2. Experiment 2: Navigation on a Static Obstacles Environment

The second experiment involves static obstacles placed along the path; therefore 16 were included in the environment. Figure 10 depicts how they were distributed; it also presents the trajectories traveled by the robot, when each method was evaluated. In this attempt, the start and goal points were set as
S t a r t = { [ 16.5 , 17.5 , π ] } ,
G o a l = { [ 2.2 , 1.1 , π ] } .
The same three intermediate points were considered (with adjustments in robot orientation); in this regard, the path consists of
P a t h = { [ 16.5 , 17.5 , π ] ; [ 10.0 , 17.5 , π ] ; [ 5.25 , 15.5 , π / 2 ] ; [ 5.25 , 8.3 , π / 2 ] ; [ 2.2 , 1.1 , π ] } T .
As can be seen in Figure 10, our proposal retains the ability to generate smoother trajectories than the comparative methods, even in the presence of obstacles. While algorithms such as RRM and PRM generated the most irregular paths, this weakness implies that for these algorithms, the robot must travel longer paths before reaching the goal. In addition, all algorithms were able to avoid the obstacles; however, for RRT, BiRRT and HybridAStar, the paths depicted a high risk of collision, in contrast to the proposed method, in which there is less problem to avoid obstacles.
Table 2 shows the overall quantitative results obtained after running each algorithm 10 times. Obstacle avoidance, which is conditional on the clearance metric, shows that algorithms such as RRT and BiRRT were more prone to object collision, and thus failed to reach the goal in some runs. The proposed method followed by HybridAStar navigated safely through the obstacles, at distances of 0.472 m and 0.390 m, respectively. Additionally, for the path smoothness metric, the smallest value was obtained by our proposal with 0.569, followed by the HybridAstar method with 0.911 . Regarding the path length that the robot had to travel before reaching the goal, it is observed that all comparative methods required an average of 2, 4, 5 and up to 7 m more than our proposal. Finally, the inclusion of obstacles reduced the efficiency of some methods. For instance, the RRT, BiRRT and PRM algorithms did not allow the robot to reach the goal in some executions, unlike the proposed method with the highest operating efficiency since it drove the robot toward the goal in all executions, although some extra time was required. Obviously, the linear and angular velocities adjustment has a direct impact on the travel time metric.
Both experiments demonstrated that the current proposal has remarkable performance. There are, however, limitations that should be addressed to improve the efficiency. The mechanical odometry should be replaced by inertial or visual odometry to increase freedom of movement. If the granularity of the detection zones is increased, then the inputs to the fuzzy system will also increase. This condition may be untreatable since the computational cost would increase exponentially by increasing the rule set size, unless such a method as fuzzy rule interpolation is considered.

4. Conclusions

In this study, we submitted a reactive type-2 fuzzy approach for the real-time control of differential mobile robot navigation. The proposal was structured around three type-2 fuzzy controllers that developed behaviors for avoiding obstacles, goal reaching (implicitly, path recovering) as well as a selector between these two behaviors, according to the current condition during navigation. Through a couple of experiments, the performance of our proposal was quantitatively demonstrated, highlighting its ability to avoid obstacles while smooth paths are generated. Apart from the foregoing, this allowed reaching the goal with a much smaller displacement than the comparative methods. To demonstrate the repeatability of results to reach the goal, each of the experiments was repeated 10 times, from which we verified that our proposal was able to reach the goal with 100 % effectiveness.
For future research, the inference tree will be executed in real time locally in the same robot, in such a way that it is not required to use high-performance software to perform this task. Additionally, work will be conducted to be able to navigate in environments with dynamic obstacles.

Author Contributions

Formal analysis, D.M.-V., A.L.-Á., A.R.-C. and J.R.; Investigation, D.M.-V., A.L.-Á., A.R.-C. and J.R.; Methodology, D.M.-V.; Software, D.M.-V., V.V.-R., A.L.-Á., A.R.-C. and M.M.-C.; Supervision, D.M.-V.; Validation, D.M.-V., V.V.-R., A.L.-Á. and M.M.-C.; Writing—original draft, D.M.-V., V.V.-R., A.L.-Á., A.R.-C. and J.R.; Writing—review and editing, D.M.-V., V.V.-R., A.R.-C. and J.R. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Acknowledgments

The authors thank CONACYT, as well as Tecnológico Nacional de México/Centro Nacional de Investigación y Desarrollo Tecnológico for their support.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Corke, P. Robotics and Control: Fundamental Algorithms in MATLAB®; Springer Nature: Cham, Switzerland, 2021; Volume 141. [Google Scholar]
  2. Gutiérrez, C.A.A.; Moreno, L.; Garrido, S. Dexterous Robotic Motion Planning Using Intelligent Algorithms. Ph.D. Thesis, Universidad Carlos III de Madrid, Madrid, Spain, 2015. [Google Scholar]
  3. Dijkstra, E.W. A note on two problems in connexion with graphs. In Edsger Wybe Dijkstra: His Life, Work, and Legacy; ACM: New York, NY, USA, 2022; pp. 287–290. [Google Scholar]
  4. Hart, P.E.; Nilsson, N.J.; Raphael, B. A formal basis for the heuristic determination of minimum cost paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  5. Nash, A.; Daniel, K.; Koenig, S.; Felner, A. Theta*: Any-angle path planning on grids. In Proceedings of the Twenty-Second AAAI Conference on Artificial Intelligence, Vancouver, BC, Canada, 22–26 July 2007; Volume 7, pp. 1177–1183. [Google Scholar]
  6. Bai, X.; Yan, W.; Ge, S.S. Distributed task assignment for multiple robots under limited communication range. IEEE Trans. Syst. Man Cybern. Syst. 2021, 52, 4259–4271. [Google Scholar] [CrossRef]
  7. Liu, L.; Lin, J.; Yao, J.; He, D.; Zheng, J.; Huang, J.; Shi, P. Path planning for smart car based on Dijkstra algorithm and dynamic window approach. Wirel. Commun. Mob. Comput. 2021, 2021, 8881684. [Google Scholar] [CrossRef]
  8. Zhu, D.D.; Sun, J.Q. A new algorithm based on Dijkstra for vehicle path planning considering intersection attribute. IEEE Access 2021, 9, 19761–19775. [Google Scholar] [CrossRef]
  9. Khadr, M.S., Sr.; Beaber, S.I., Sr.; Said, E.; Elmayyah, W.M.; Hussein, W.M. Indoor path-planning for a tracked mobile robot using Dijkstra’s algorithm and Ros. In Proceedings of the Unmanned Systems Technology XXIII, Online, 12–16 April 2021; SPIE: Philadelphia, PA, USA, 2021; Volume 11758, pp. 211–220. [Google Scholar]
  10. Fransen, K.; van Eekelen, J. Efficient path planning for automated guided vehicles using A*(Astar) algorithm incorporating turning costs in search heuristic. Int. J. Prod. Res. 2021, 1–19. [Google Scholar] [CrossRef]
  11. Tang, G.; Tang, C.; Claramunt, C.; Hu, X.; Zhou, P. Geometric A-star algorithm: An improved A-star algorithm for AGV path planning in a port environment. IEEE Access 2021, 9, 59196–59210. [Google Scholar] [CrossRef]
  12. Liu, Z.; Liu, H.; Lu, Z.; Zeng, Q. A dynamic fusion pathfinding algorithm using delaunay triangulation and improved A-star for mobile robots. IEEE Access 2021, 9, 20602–20621. [Google Scholar] [CrossRef]
  13. Bailey, J.P.; Nash, A.; Tovey, C.A.; Koenig, S. Path-length analysis for grid-based path planning. Artif. Intell. 2021, 301, 103560. [Google Scholar] [CrossRef]
  14. Bai, X.; Yan, W.; Cao, M. Clustering-based algorithms for multivehicle task assignment in a time-invariant drift field. IEEE Robot. Autom. Lett. 2017, 2, 2166–2173. [Google Scholar] [CrossRef] [Green Version]
  15. Bai, X.; Yan, W.; Ge, S.S.; Cao, M. An integrated multi-population genetic algorithm for multi-vehicle task assignment in a drift field. Inf. Sci. 2018, 453, 227–238. [Google Scholar] [CrossRef]
  16. Petereit, J.; Emter, T.; Frey, C.W.; Kopfstedt, T.; Beutel, A. Application of hybrid A* to an autonomous mobile robot for path planning in unstructured outdoor environments. In Proceedings of the ROBOTIK 2012; 7th German Conference on Robotics, Munich, Germany, 21–22 May 2012; VDE: Hamburg, Germany, 2012; pp. 1–6. [Google Scholar]
  17. LaValle, S.M.; Kuffner, J.J., Jr. Randomized kinodynamic planning. Int. J. Robot. Res. 2001, 20, 378–400. [Google Scholar] [CrossRef]
  18. Kuffner, J.J.; LaValle, S.M. RRT-connect: An efficient approach to single-query path planning. In Proceedings of the 2000 ICRA, Millennium Conference, IEEE International Conference on Robotics and Automation, Symposia Proceedings (Cat. No. 53 00CH37065), San Francisco, CA, USA, 24–28 April 2000; IEEE: New York, NY, USA, 2000; pp. 995–1001. [Google Scholar]
  19. Kavraki, L.E.; Svestka, P.; Latombe, J.C.; Overmars, M.H. Probabilistic roadmaps for path planning in high-dimensional configuration spaces. IEEE Trans. Robot. Autom. 1996, 12, 566–580. [Google Scholar] [CrossRef] [Green Version]
  20. Ollero, A.; Amidi, O. Predictive path tracking of mobile robots. Application to the CMU Navlab. In Proceedings of the 5th International Conference on Advanced Robotics, Robots in Unstructured Environments, ICAR, Pisa, Italy, 19–22 June 1991; Volume 91, pp. 1081–1086. [Google Scholar]
  21. Tiep, D.K.; Lee, K.; Im, D.-Y.; Kwak, B.; Ryoo, Y.-J. Design of fuzzy-PID controller for path tracking of mobile robot with differential drive. Int. J. Fuzzy Log. Intell. Syst. 2018, 18, 220–228. [Google Scholar] [CrossRef]
  22. Ammar, H.H.; Azar, A.T. Robust path tracking of mobile robot using fractional order PID controller. In Proceedings of the International Conference on Advanced Machine Learning Technologies and Applications, Cairo, Egypt, 28–30 March 2019; Springer: Berlin/Heidelberg, Germany, 2019; pp. 370–381. [Google Scholar]
  23. Duchoň, F.; Babinec, A.; Kajan, M.; Beňo, P.; Florek, M.; Fico, T.; Jurišica, L. Path planning with modified a star algorithm for a mobile robot. Procedia Eng. 2014, 96, 59–69. [Google Scholar] [CrossRef] [Green Version]
  24. Wang, B. Path Planning of Mobile Robot Based on A* Algorithm. In Proceedings of the 2021 IEEE International Conference on Electronic Technology, Communication and Information (ICETCI), Changchun, China, 27–29 August 2021; IEEE: New York, NY, USA, 2021; pp. 524–528. [Google Scholar]
  25. Singh, N.H.; Thongam, K. Mobile robot navigation using fuzzy logic in static environments. Procedia Comput. Sci. 2018, 125, 11–17. [Google Scholar] [CrossRef]
  26. Shiltagh, N.A.; Jalal, L.D. Path planning of intelligent mobile robot using modified genetic algorithm. Int. J. Soft Comput. Eng. 2013, 3, 31–36. [Google Scholar]
  27. Lamini, C.; Benhlima, S.; Elbekri, A. Genetic algorithm based approach for autonomous mobile robot path planning. Procedia Comput. Sci. 2018, 127, 180–189. [Google Scholar] [CrossRef]
  28. Dirik, M.; Castillo, O.; Kocamaz, A.F. Gaze-guided control of an autonomous mobile robot using type-2 fuzzy logic. Appl. Syst. Innov. 2019, 2, 14. [Google Scholar] [CrossRef] [Green Version]
  29. Wahhab, O.; Araji, A. Path planning and control strategy design for mobile robot based on hybrid swarm optimization algorithm. Int. J. Intell. Eng. Syst. 2021, 14, 565–579. [Google Scholar] [CrossRef]
  30. Dai, X.; Long, S.; Zhang, Z.; Gong, D. Mobile robot path planning based on ant colony algorithm with A* heuristic method. Front. Neurorobot. 2019, 13, 15. [Google Scholar] [CrossRef]
  31. Gul, F.; Rahiman, W.; Nazli Alhady, S.S. A comprehensive study for robot navigation techniques. Cogent Eng. 2019, 6, 1632046. [Google Scholar] [CrossRef]
  32. Ruan, X.; Ren, D.; Zhu, X.; Huang, J. Mobile robot navigation based on deep reinforcement learning. In Proceedings of the 2019 Chinese Control and Decision Conference (CCDC), Nanchang, China, 3–5 June 2019; IEEE: New York, NY, USA, 2019; pp. 6174–6178. [Google Scholar]
  33. Li, S.; Su, W.; Huang, R.; Zhang, S. Mobile Robot Navigation Algorithm Based on Ant Colony Algorithm with A* Heuristic Method. In Proceedings of the 2020 4th International Conference on Robotics and Automation Sciences (ICRAS), Chengdu, China, 6–8 June 2020; IEEE: New York, NY, USA, 2020; pp. 28–33. [Google Scholar]
  34. Yang, H.; Qi, J.; Miao, Y.; Sun, H.; Li, J. A new robot navigation algorithm based on a double-layer ant algorithm and trajectory optimization. IEEE Trans. Ind. Electron. 2018, 66, 8557–8566. [Google Scholar] [CrossRef] [Green Version]
  35. Kumar, S.; Pandey, K.K.; Muni, M.K.; Parhi, D.R. Path planning of the mobile robot using fuzzified advanced ant colony optimization. In Innovative Product Design and Intelligent Manufacturing Systems; Springer: Berlin/Heidelberg, Germany, 2020; pp. 1043–1052. [Google Scholar]
  36. Mohanta, J.C.; Keshari, A. A knowledge based fuzzy-probabilistic roadmap method for mobile robot navigation. Appl. Soft Comput. 2019, 79, 391–409. [Google Scholar] [CrossRef]
  37. Chen, C.H.; Lin, C.J.; Jeng, S.Y.; Lin, H.Y.; Yu, C.Y. Using ultrasonic sensors and a knowledge-based neural fuzzy controller for mobile robot navigation control. Electronics 2021, 10, 466. [Google Scholar] [CrossRef]
  38. Gatesichapakorn, S.; Takamatsu, J.; Ruchanurucks, M. ROS based autonomous mobile robot navigation using 2D LiDAR and RGB-D camera. In Proceedings of the 2019 First International Symposium on Instrumentation, Control, Artificial Intelligence, and Robotics (ICA-SYMP), Bangkok, Thailand, 16–18 January 2019; IEEE: New York, NY, USA, 2019; pp. 151–154. [Google Scholar]
  39. Tsai, C.Y.; Nisar, H.; Hu, Y.C. Mapless LiDAR Navigation Control of Wheeled Mobile Robots Based on Deep Imitation Learning. IEEE Access 2021, 9, 117527–117541. [Google Scholar] [CrossRef]
  40. Mihelj, M.; Bajd, T.; Ude, A.; Lenarčič, J.; Stanovnik, A.; Munih, M.; Rejc, J.; Šlajpah, S. Robotics; Springer: Berlin/Heidelberg, Germany, 2019. [Google Scholar]
  41. Mendel, J.M. Uncertain rule-based fuzzy systems. In Introduction and New Directions; Springer: Berlin/Heidelberg, Germany, 2017; p. 684. [Google Scholar]
  42. Castillo, O.; Aguilar, L.T. Type-2 Fuzzy Logic in Control of Nonsmooth Systems; Springer: Berlin/Heidelberg, Germany, 2018. [Google Scholar]
  43. Lei, T.; Luo, C.; Sellers, T.; Rahimi, S. A bat-pigeon algorithm to crack detection-enabled autonomous vehicle navigation and mapping. Intell. Syst. Appl. 2021, 12, 200053. [Google Scholar] [CrossRef]
Figure 1. Composition of used system.
Figure 1. Composition of used system.
Machines 10 00660 g001
Figure 2. LIDAR coverage.
Figure 2. LIDAR coverage.
Machines 10 00660 g002
Figure 3. Differential robot odometry.
Figure 3. Differential robot odometry.
Machines 10 00660 g003
Figure 4. Proposed type-2 fuzzy inference tree.
Figure 4. Proposed type-2 fuzzy inference tree.
Machines 10 00660 g004
Figure 5. Type-2 fuzzy sets in the inputs.
Figure 5. Type-2 fuzzy sets in the inputs.
Machines 10 00660 g005
Figure 6. Type-2 Fuzzy Sets in the Outputs.
Figure 6. Type-2 Fuzzy Sets in the Outputs.
Machines 10 00660 g006
Figure 7. Real navigation environment.
Figure 7. Real navigation environment.
Machines 10 00660 g007
Figure 8. Real measurements and occupation map of the work environment.
Figure 8. Real measurements and occupation map of the work environment.
Machines 10 00660 g008
Figure 9. Paths obtained during the navigation on an obstacles-free environment.
Figure 9. Paths obtained during the navigation on an obstacles-free environment.
Machines 10 00660 g009
Figure 10. Paths obtained during the navigation on a static obstacles environment.
Figure 10. Paths obtained during the navigation on a static obstacles environment.
Machines 10 00660 g010
Table 1. Quantitative results for the first experiment.
Table 1. Quantitative results for the first experiment.
MethodClearance (m)Path Smoothness
(rad)
Path Length (m)Travel Time (s)Success Rate
Hybrid AStar0.413 ± 0.0640.602 ± 0.13222.687 ± 0.840449 ± 41 100 %
RRT0.355 ± 0.0822.336 ± 0.61524.941 ± 1.413418 ± 33 100 %
BiRRT0.409 ± 0.0910.826 ± 0.26530.019 ± 2.534396 ± 26 100 %
PRM0.399 ± 0.0731.984 ± 0.47826.790 ± 1.657280 ± 19 100 %
Proposed0.503 ± 0.0580.236 ± 0.09718.289 ± 0.283403 ± 15 100 %
Table 2. Quantitative results for the second experiment.
Table 2. Quantitative results for the second experiment.
MethodClearance (m)Path Smoothness
(rad)
Path Length (m)Travel Time (s)Success Rate
Hybrid AStar0.390 ± 0.0750.911 ± 0.24229.182 ± 1.222538 ± 46 100 %
RRT0.297 ± 0.0882.616 ± 0.60731.724 ± 2.616495 ± 37 90 %
BiRRT0.201 ± 0.0962.983 ± 0.62432.614 ± 2.977428 ± 28 80 %
PRM0.368 ± 0.0723.421 ± 0.71234.007 ± 3.150345 ± 23 90 %
Proposed0.472 ± 0.0470.569 ± 0.18627.652 ± 0.535570 ± 18 100 %
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Mújica-Vargas, D.; Vela-Rincón, V.; Luna-Álvarez, A.; Rendón-Castro, A.; Matuz-Cruz, M.; Rubio, J. Navigation of a Differential Wheeled Robot Based on a Type-2 Fuzzy Inference Tree. Machines 2022, 10, 660. https://0-doi-org.brum.beds.ac.uk/10.3390/machines10080660

AMA Style

Mújica-Vargas D, Vela-Rincón V, Luna-Álvarez A, Rendón-Castro A, Matuz-Cruz M, Rubio J. Navigation of a Differential Wheeled Robot Based on a Type-2 Fuzzy Inference Tree. Machines. 2022; 10(8):660. https://0-doi-org.brum.beds.ac.uk/10.3390/machines10080660

Chicago/Turabian Style

Mújica-Vargas, Dante, Viridiana Vela-Rincón, Antonio Luna-Álvarez, Arturo Rendón-Castro, Manuel Matuz-Cruz, and José Rubio. 2022. "Navigation of a Differential Wheeled Robot Based on a Type-2 Fuzzy Inference Tree" Machines 10, no. 8: 660. https://0-doi-org.brum.beds.ac.uk/10.3390/machines10080660

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