Next Article in Journal
Optimization Algorithm for Multiple Phases Sectionalized Modulation Jamming Based on Particle Swarm Optimization
Next Article in Special Issue
A Smart Many-Core Implementation of a Motion Planning Framework along a Reference Path for Autonomous Cars
Previous Article in Journal
Compact UWB Band-Notched Antenna with Integrated Bluetooth for Personal Wireless Communication and UWB Applications
Previous Article in Special Issue
Trapezoidal Motion Profile to Suppress Residual Vibration of Flexible Object Moved by Robot
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Free Navigation of an AGV to a Non-Static Target with Obstacle Avoidance

1
System Engineering and Automation Control Department, University of the Basque Country (UPV/EHU), Nieves Cano, 12, 01006 Vitoria-Gasteiz, Spain
2
Department of Nuclear and Fluid Mechanics, University of the Basque Country (UPV/EHU), Nieves Cano, 12, 01006 Vitoria-Gasteiz, Spain
3
Department of Mechanical Engineering, University of the Basque Country (UPV/EHU), Nieves Cano, 12, 01006 Vitoria-Gasteiz, Spain
*
Author to whom correspondence should be addressed.
Electronics 2019, 8(2), 159; https://doi.org/10.3390/electronics8020159
Submission received: 8 November 2018 / Revised: 21 January 2019 / Accepted: 23 January 2019 / Published: 1 February 2019
(This article belongs to the Special Issue Motion Planning and Control for Robotics)

Abstract

:
The industry is changing in order to improve the economy sector. This is the reason why technology is improving and developing new devices. The autonomous guided vehicle with free navigation is a new machine, which uses different techniques to move such as mapping, localization, path planning, and path following. In this paper, a path following is proposed. The path following is called moving to a point, which uses the proportional distance between the target and the autonomous guided vehicles (AGV) to calculate the velocity and direction. If some obstacles appear in the trajectory, however, the vehicle stops. Instead of stopping the machine, by using moving to a point logic, an obstacle avoidance function will be implemented. In this implementation, different parameters can be configured, such as: security distance, which determinates when the obstacle avoidance must correct the pose; and proportional values, which modify the velocity and steering commands. It is also compared to a dynamic window approach (DWA) obstacle avoidance solution. Additionally, the AGV navigates to a non-static target with a path following algorithm.

1. Introduction

Nowadays, the industry is changing its organizational structure. This change is known as Industry 4.0, which is intended to improve the economy sector. Companies will become more intelligent by using diverse techniques [1]. To make this possible, new programmable logic controller (PLC) devices will be introduced, which will transfer huge calculation and information capabilities, and will also be used to introduce more robots in production lines etc. Apart from introducing new devices, there will also be increased connectivity into the same information system. As a result, production can be adapted to demand and become more efficient [2]. In the end, the aim is to have a greater production capability, better quality, and optimization in production resources.
Robotics is changing the production concept and adapting to this new era. Today, robots and humans work in the same areas. Djuric et al. [3] commented that these robots are known as Cobots. Thanks to power and force limitations, the employees can stay together in the same working area. According to Cherubini et al. [4], when they are cooperating, ergonomic concerns can be reduced, due to the physical job and cognitive loading. It also provides improvements on safety, quality, and productivity.
In order to obtain greater flexibility and efficiency, not only will the robots change, but the autonomous guided vehicle (AGV) also introduces new updates. Nowadays, these AGVs only move using magnetic fields, so they do not have any intelligence, which makes it too difficult to change logistics areas [5]. However, to introduce a free navigation intelligence, mapping, localization, path planning, and path following aspects have to be implemented.
Mapping and localization are solved using simultaneous localization and mapping (SLAM) [6,7]. Considering the mobile robot has no idea about where it is and where it is going to be, with SLAM it is possible to learn the environment characteristics in order to locate the vehicle. In the case that it was necessary to move it, another algorithm would be required. Here is where path planning and path following take part. Elsheikh et al. [8] confirmed, the differences between these, lie in how much the robot can do.
In path planning, the start and end points are given and then the vehicle must plan the best path. The robot navigation problem can be described as the process of determining a suitable and safe path, avoiding obstacles and collisions [9], therefore, the AGV navigates without any path following restrictions and moves wherever it wants to arrive at its goal position. There are different alternatives which can be implemented, such as swarm optimization (SO), which is based on particle swarm optimization as Ever [10] analysed, Hu et al. [11] studied dynamic path planning, and dynamic movements primitives is explained by Mei et al. [12].
Apart from these, there are other well-known path planning algorithms, such as the dynamic window approach developed by Fox et al. [13], vector field histogram related by Borenstein et al. [14], TangentBug and PointsBug, as compared by Buniyamin et al. [15], and the rapidly exploring random tree, as Adiyatov et al. [16] explained. Most of these well-known algorithms are used in actual applications.
Otherwise, in path following problems, the user gives the robot the path and it should only follow it. According to Wang [17], these controllers are designed to obtain the minimal lateral distance, as well as the heading between the vehicle and the command path to control the vehicle speed and steering to follow a specified path. Algorithms like pure pursuit [18] mentioned, moving to a point [19], and proportional navigation [20].
Sebi et al. [21] advised that apart from using SLAM, path following, and path planning, another algorithm is required. Without any obstacle avoidance intelligence, the AGV makes a safety stop to prevent collision with an object. This is the reason for the proposal of different obstacle avoidance algorithms [22,23,24]. In most cases the obstacles are detected using cameras, LIDAR, or ultrasonic sensors as Amin et al. [25] and Martinez et al. [26] explained. In the end, all of these sensors are trying to avoid making contact with the obstacle. However, there are some cases, that when the obstacle is detected as making a collision, the force is analyzed with piezoelectric sensors like Wooten et al. [27] studied.
The main goal of the present study is to improve a simple path following algorithm introducing an obstacle avoidance technique. This technique is implemented using simple equations, in order to avoid large calculations in the controller. After developing the algorithm, it will be tested with a traditional motion planning algorithm to analyze the differences between both.

2. Problem Formulation

The aim is to take a commercial AGV from industrial application and use its technology to introduce an obstacle avoidance algorithm. This commercial AGV uses a LIDAR to take information from the surroundings, a programable logic controller (PLC) to control AGV periphery (motors, displays, lights, etc.) and an industrial personal computer (IPC) for the SLAM and path following algorithm. It is remarkable that the only programable hardware is the PLC, and it does not have enough capability to process huge calculations like optimization.
All hardware is connected via Ethernet to synchronize the information. The IPC sends speed ( V a g v ) and steering ( γ ) commands to the PLC, the PLC sends wheel-odometry information to the IPC, and LIDAR sends information to both the PLC and IPC.
In the Industry, it is better to use known trajectories, which is why these vehicles use only path following algorithms. In general, these algorithms are very simple and cannot avoid an obstacle. Hence, it was decided to implement an obstacle avoidance term into the path following.
Furthermore, the AGV has to arrive at a conveyor transport and synchronize its speeds with the moving target. The collaborative robot that was assembled in the AGV then takes an object from conveyor transport and moves it to another point of the factory. The objective is not to stop the conveyor transport to take that product, in order to reduce production time.
The idea of this paper is to take moving to a point mathematical equations and adapt them to implement avoidance technique. Corke [19] studied a moving to a point path following algorithm, in which the problem of moving towards a goal point ( x ,   y ) in the plane was analyzed. For this solution, the velocity of the robot considered in Equation (1) is controlled proportionally to the distance from the goal, as analysed in Equation (2).
V a g v   =   e r r o r · K v
e r r o r =   ( x x ) 2 +   ( y y ) 2
To steer towards the goal, which is represented in Equation (3), it is considered that K h is the proportional controller, and the vehicle-relative angle is analyzed in Equation (4).
γ = K h · ( θ θ ) ,   K h > 0
θ = a t a n ( y y x x )
Therefore, in the current study, a new obstacle avoidance strategy is proposed to be implemented in the moving to a point technique. It is based on measurement between the vehicle and the obstacle. Table 1 summarizes all terms and parameters used in this work.

3. Implementation of Obstacle Avoidance

A new formulation is presented in this section, so the vehicle can autonomously correct the path avoiding the obstacle. Considering the measurement of the LIDAR, it is possible to obtain the distance between the AGV and the obstacle. According to Peng et al. [22], that distance is expressed in Equation (5).
D o b s =   x o b s 2 + y o b s 2
P o b s = ( x o b s y o b s )
P a g v = ( x y )
x o b s   and   y o b s represent the relative coordinates of the distance between the AGV and the nearest obstacle defined by D o b s in Figure 1. The output of the Equation (5) can be represented in a graph. Figure 2 shows how the LIDAR measurement changes when some obstacle appears in the AGV’s way.
To use that measurement information as a correction for the steering command, the graph must start at 0 value. By subtracting the LIDAR maximum measurement range to D o b s , the answer will change. This way, when the AGV is approaching the obstacle, the value becomes more negative. This expression is analysed in equation (8) and the solution is represented in Figure 3.
C = D o b s   L i d a r m a x r a n g e
In Equation (9), a safety distance term is introduced to prevent premature correction. This safety distance maintains the AGV direction until the object is between the AGV and that distance. In case of the object being far away, the obstacle avoidance stays in standby mode. In other words, it does not interfere with the moving to a point algorithm.
A v o i d =   β · C · e α D o b s
β is a constant which adapts the intensity of the avoid function and e α D o b s is the safety implementation with a α parameter, which changes the safety distance. This avoid function adapts the AGV direction to avoid the obstacle. Therefore, this term must interact with the γ value. Instead of implementing directly the avoidance correction, it has been considered to introduce some logic between the γ value and avoid value, using a sigmoid function as shown in Equation (10).
C o m = 1 1 + e α D o b s
Regrouping all the equations, the Moving to a Point algorithm with obstacle avoidance can be summarized with Equation (11).
γ = K h · [ δ ·   C o m · A v o i d + ( 1 φ · C o m ) · ( θ θ ) ]
where δ ,   y ,   and   φ are constants, which modify the interaction with the Com function. K h is a proportional constant, which changes the measurement value to steering value. Until this point, the AGV can avoid an obstacle and it always turns to the right. In some cases, however, it is better to turn to the left so as not to lose too much time avoiding the obstacle. It can be done by analyzing the sign of the angles as represented in Equation (12).
γ =   S i g n ( A r g ( P a g v ) A r g ( P o b s ) ) · γ
The vehicle velocity can be modified considering the same logic. When the obstacle is close, the AGV must reduce its speed. Taking Equation (9) as reference, Equation (13) can be made, which considers a variation of speed changing β by μ .
A v o i d v e l =   μ · C ·   e α D o b s  
In addition, this function has to interact with the moving to a point velocity command, which is the reason why Equations (10) and (13) are combined to obtain Equation (14).
V   a g v   =   K v · [ δ · C o m · A v o i d v e l +   ( 1 φ · C o m ) · e r r o r ]
where δ and φ are constants, which modify the interaction with Com function. Finally, K v is the proportional value that changes the measurement value to velocity value.

4. AGV Kinematics Equations

In this case, a specific AGV was used, so it is necessary to specify the kinematics of that vehicle. In some cases, it is possible to use defined kinematics like Corke [19] proposed in his study. This special AGV has two motors in the front axle. The autonomous vehicle uses different speed values in each motor to steer. Both axles are connected mechanically by means of a pulley mechanism to reduce the steering radio.
The inputs of the kinematics block are the AGV velocity and direction. The output, however, is the vehicle POSE. The velocity reference ( V a g v ) is in the middle of the vehicle. When the AGV goes in a straight line, both motors ( V i   and   V d ) have the same velocity. However, if the AGV takes a curve, the motors will have different velocities.
Hence, taking Figure 4 as a reference, wheel speed can be represented in Equations (15) and (16):
V I =   γ ˙ · ( H b / 2 )
V D =   γ ˙ · ( H + b / 2 )
where H is the distance between rotation point and V c , and b is the size of the wheel axle. Taking into account Equations (15) and (16), γ ˙ can be defined by motors velocities presented in Equation (17):
γ ˙ = V D V I b
The V A G V is split in x ˙ and y ˙ absolute coordinates.
V x =   V   a g v   · c o s θ
V y =   V   a g v   · s i n θ
V C and   V a g v are related each other, since the vehicle is considered as a solid element and the velocity propagates along all the structure, as illustrated in Figure 5.
V   a g v   =   V c · c o s γ
The velocity V r o t represented in Figure 5 turns the vehicle and generates the rotation in the middle of the AGV. The rotation of the vehicle can be defined with Equations (21) and (22):
θ ˙ L 2 = V r o t
V r o t =   V c · s i n γ
Combining (21) and (22), Equation (23) is obtained.
θ ˙ = 2 L · V c · s i n γ
Considering Equations (18–20) and (23), it is possible to define the vehicle dynamics in Equation (24):
| V x V y θ ˙ | =   | c o s γ · c o s θ   c o s γ · s i n θ   2 L · s i n γ | V c
where L is the wheelbase, θ is the AGV angle position in absolute coordinates, and γ is the value of the direction, which comes from the algorithm.

5. Implementation of Model

Once the dynamic block is ready, it is time to analyze this algorithm. Simulation software predicts what would happen in a “real” situation. The example scenario that comes with it has been modified and adapted to a more realistic surrounding.
It is possible to add sensors to analyze the area in this program. In this case, a LIDAR sensor has been implemented to take measurements from the surroundings. This sensor has 51 lines distributed from –π/2 rad to π/2 rad and there is a measurement for each line. Hence, the centre line of the LIDAR is located at 0 rad and it is the line 26. Figure 6 shows how the lines change the color from blue to green, when the LIDAR detects some object.
There are two important blocks to interact with that library in Figure 7. One is to represent the vehicle movement and the other one is to take measurements that form the area.

6. Results

Figure 8 shows the test area, which has three walls, two obstacles, and a moving point. This moving point is the target for the AGV and it is a non-static point.
Figure 9 shows the AGV trajectory after executing the simulation. It can be appreciated how the vehicle avoids the objects and selects where to turn depending on the obstacle localization.
In addition, the AGV can follow a moving goal using the moving to a point algorithm. As expected, there is some error because this path following algorithm uses a proportional function. Therefore, some error occurs when it has a non-static goal.
Figure 10 shows the error between the moving point and the AGV. The error has been calculated as 0.4 m. This gap can be modified by adapting the K v parameter.
After avoiding the obstacles, the system has some damping until it is stabilized. This damping can be modified adapting the K h value. If the value of K h increases, the AGV moves faster and can steer quicker. Figure 11 illustrates the trajectory of the AGV with different K h values.
Apart from modifying the direction of the vehicle, the velocity is reduced to be more precise in the avoidance maneuver. This speed variation is represented in Figure 12. The avoiding algorithm calculates a velocity correction (red line) and this correction is implemented on the moving to a point velocity term (blue Line). After avoiding the obstacle, the safety term stops actuating. In 20 sample times, the avoidance stops correcting the speed.

7. Dynamic Window Approach Comparison

The next step after testing the avoidance algorithm consists of comparing it with a classic motion planning solution. A well-known dynamic window approach (DWA) [13] algorithm is used. DWA is divided into two parts: The first part is search space, in which the different possible V a g v and γ ˙ are considered. This section is subdivided into three steps: circular trajectories, where it is calculated a two-dimensional velocity ( V a g v ,   γ ˙ ) space, admissible velocities to restrict the admissible velocities ensuring safe trajectories, and dynamic window, which analyses only those velocities that can be reached on a short time interval considering robot acceleration limitations.
The second part is an optimization. The optimization is represented by Equation (25):
G ( V a g v ,   γ ˙ ) =   σ D ( α D · heading ( V a g v ,   γ ˙ ) + β D · d i s t ( V a g v ,   γ ˙ ) + γ D · v e l ( V a g v ,   γ ˙ ) )
Moreover, this second part is also subdivided into three steps: target heading, which is a measure of progress toward the goal, clearance, which is the distance to the closest obstacle, and velocity, which is considered the forward velocity of the robot.
Before starting the simulation of both algorithms, there are some aspects that can be appreciated without any execution. On the one hand, DWA uses an optimization term and normally these equations require a high computational capability. For the AGV that is used in our application, it is impossible to execute and process this optimization over a short period of time. That is the reason for the development of POA. Otherwise, with DWA it is possible to generate a proper trajectory, as it always selects the best path according to the space conditions. Furthermore, POA does not consider the vehicle kinematics, hence it makes a simpler calculation to avoid the obstacle. In order words, POA does not calculate a trajectory, it just modifies the path following command to change the direction and velocity when some obstacle appears in front of the vehicle. As a result, when some object is detected, the speed will be reduced to avoid it safely. DWA, however, always selects a trajectory considering the top speed value and minor acceleration loss.
On the other hand, in both cases adjustable gains are used to optimize the algorithms, making it more flexible to adapt to different surroundings or kinematics conditions. In addition, DWA can select which side turns the vehicle, in order to avoid the obstacle using the trajectory optimization. POA, such as the other algorithm, makes the same action. Otherwise, it uses Equation (12) to determinate which side turns the AGV.
In order to perform an easy comparison between both algorithms, a new simple scenario has been designed (see Figure 13). There are three elements in the scenario: an object, a moving obstacle, and the static goal position. With the moving obstacle, it is possible to analyze human–robot collaboration. This moving obstacle is considered to be a human and the AGV must avoid the collision.
Using Table 2 variables, the result of both algorithm executions is shown in Figure 14. Where the black represents the static obstacle, the red draws goal point, the pink represents the moving obstacle, the pink dashed line shows moving obstacle trajectory, green lines represent DWA possible trajectories, and blue lines represent the algorithm trajectory.
For this particular example, the DWA algorithm had more problems to avoid the moving obstacle than POA. DWA, with Table 3 optimization constant values, cannot fit an optimal trajectory to avoid the moving obstacle. To have a better idea of how the algorithms act with the mobile object, Figure 15 represents different time instants of the AGV trajectory. In the end, the algorithm does not avoid the moving obstacle, until the obstacle is a particular distance away from the AGV. Hence, it would be a problem if the vehicle did not have enough D o b s .
Figure 16 shows the avoidance progress for POA. The POA algorithm tries to avoid the moving obstacle until the sign of Equation (12) changes. When that sign changes, the AGV continues to the goal without any problem.
In order to stop simulating, new different starting points for the AGV are implemented. This makes it possible to analyze and compare what happens with the vehicle on different cases. Apart from this, DWA configurable constants are changed to reduce the speed window size. γ D = 2.0 is used, in order to reduce the effect that is shown in Figure 15, in which the AGV needed more D o b s to avoid the obstacle.
In Table 3 different simulation results are shown, and it is necessary to consider that speed arriving at goal is the speed value at 1 s before arriving to the goal. Additionally, a static object is implemented, which is an x = 8 and y = 9 position, and a moving point, which starts in x = 0 and y = 20 position and ends in x = 40 and y = −20 position with 0.92 m/s constant speed. In addition, the goal is located in an x = 20 y = 20 position. All of these parameters also are used in the Figure 14 simulation.
Looking at Table 3, in general, DWA needs more space to avoid the obstacles with this configuration. That is why the value of D o b s is larger than POA. Hence, the odometry in DWA is going to be higher, because both parameters are proportional.
If total time is compared, however, the situation changes. POA uses more time to arrive at the goal position. When AGV is approximating the goal, it will reduce the speed more dramatically, as represented by the speed arriving at goal column. In the end, the difference between both approximation speeds is around 0.46 m/s. Otherwise, POA has the best mean speed and the difference between both mean speeds is about 0.07 m/s, which is negligible.
To give a general idea about algorithms failure, Figure 17, which represents the worst trajectory of POA in comparison with DWA, and Figure 18, which analyzes the worst trajectory of DWA in comparison with POA, are shown. To consider which is the worst trajectory, the largest odometry was analyzed, due to AGV diverting more from the ideal path, which is a straight line from the starting point to the goal.
In Figure 17, POA had a greater difficulty deciding where to avoid the moving obstacle. AGV tried to follow it until the obstacle was so far away that the vehicle stopped detecting it. A similar occurrence is observed in Figure 18. Instead of POA failing to avoid the obstacle, this time DWA failed. The dynamic window did not have enough space to pass the obstacle and it waited until having enough distance to avoid it. In both cases, the algorithms have a bad reaction with the moving obstacle, hence for future work it could be possible to analyze the space and detect moving obstacles. In case that some moving obstacle appears, the AGV stops and wait until the obstacle disappears.
Overall, both algorithms work in the same conditions, though depending on the algorithm configuration the answer of the simulation can change. There are some cases in which the DWA trajectories are worst, and other times the POA’s paths are not good enough. Generally, DWA approximates the goal with a higher speed and, depending on the application, this speed must be controlled to safely arrive. POA, however, gives less space between the AGV and object. In the end, this could be a problem if the AGV moves around humans.

8. Conclusions

The solution proposed in this paper can highly improve a simple path following algorithm behavior. It gives more intelligence to the AGV, a result of the obstacle avoidance parameters. Moreover, it introduces more flexibility to the algorithm, because there are some variables which change the performance. Additionally, POA uses a simple equation to implement on a PLC, which is the only hardware available on the selected AGV. This hardware limitation is an important feature, because not all equipment supports large calculation capabilities, such as DWA, which uses an optimization function to select the best trajectory.
The optimization function gives the opportunity to analyze some trajectories and then select the best one. However, POA just modifies the path following trajectory depending on the gap between the AGV and obstacle. In other words, the algorithm does not optimize the trajectory.
In addition, POA has a good performance compared with traditional DWA algorithms. Both have similar behavior in avoiding the static obstacle. Furthermore, both can select which side turns the vehicle, in order to avoid the obstacle. DWA, however, tries to divert more from the obstacle, hence the AGV needs more space to avoid the obstacle. To solve this divergent, the algorithm always tries to go at maximum speed and it arrives faster than POA.
Apart from that, there is a considerable arriving speed value difference between both algorithms. For this application, the AGV must be able to cooperate with humans. Hence it would be safer for the AGV to arrive to the goal with less speed. Otherwise humans may interpret the fast approach as harmful. There is another similar situation, in which the vehicle is avoiding the human and it maintains a gap during the maneuver as an avoidance strategy.
It is remarkable that both algorithms can avoid a moving obstacle. Otherwise, they would need to be improved to avoid these kinds of obstacles. In future work, they could be improved using dynamic parameter values to change algorithm behavior depending on the situation. In some cases, it would be better to reduce AGV speed and wait until the obstacle disappears, while in other ones it would be possible to increase the speed to reduce commute time. In other situations, it could be possible to maintain a gap with the obstacle, for example, when the AGV has to avoid a box which is in its way. Moreover, it is important to control how much the AGV diverts from the obstacle, depending on the scenario this feature must be controlled. In industrial areas, for example, there is not much space to avoid the obstacle.

Author Contributions

D.T.-F.-B., E.Z. and U.F.-G. developed and programmed the simulation set up. They also wrote the manuscript. I.A. and I.U. made constructive contributions in the process of preparing the paper.

Acknowledgments

The funding from the Government of the Basque Country and the University of the Basque Country UPV/EHU through the SAIOTEK (S-PE11UN112) and EHU12/26 research programs, respectively, is gratefully acknowledged.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Pereira, A.C.; Romero, F. A review of the meanings and the implications of the Industry 4.0 concept. Procedia Manuf. 2017, 13, 1206–1214. [Google Scholar] [CrossRef]
  2. Zhong, R.Y.; Xu, X.; Klotz, E.; Newman, S.T. Intelligent Manufacturing in the Context of Industry 4.0: A Review. Engineering 2017, 3, 616–630. [Google Scholar] [CrossRef]
  3. Djuric, A.M.; Urbanic, R.J.; Rickli, J.L. A Framework for Collaborative Robot (CoBot) Integration in Advanced Manufacturing Systems. SAE Int. J. Mater. Manuf. 2016, 9, 457–464. [Google Scholar] [CrossRef]
  4. Cherubini, A.; Passama, R.; Crosnier, A.; Lasnier, A.; Fraisse, P. Collaborative manufacturing with physical human–robot interaction. Robot. Comput.-Integr. Manuf. 2016, 40, 1–13. [Google Scholar] [CrossRef] [Green Version]
  5. Cardarelli, E.; Digani, V.; Sabattini, L.; Secchi, C.; Fantuzzi, C. Cooperative cloud robotics architecture for the coordination of multi-AGV systems in industrial warehouses. Mechatronics 2017, 45, 1–13. [Google Scholar] [CrossRef]
  6. Mustafa, M.; Stancu, A.; Delanoue, N.; Codres, E. Guaranteed SLAM—An interval approach. Robot. Auton. Syst. 2018, 100, 160–170. [Google Scholar] [CrossRef]
  7. Nakajima, K.; Premachandra, C.; Kato, K. 3D environment mapping and self-position estimation by a small flying robot mounted with a movable ultrasonic range sensor. J. Electr. Syst. Inf. Technol. 2017, 4, 289–298. [Google Scholar] [CrossRef]
  8. Elsheikh, E.A.; El-Bardini, M.A.; Fkirin, M.A. Practical path planning and path following for a non-holonomic mobile robot based on visual servoing. In Proceedings of the 2016 IEEE Information Technology, Networking, Electronic and Automation Control Conference, Chongqing, China, 20–22 May 2016; pp. 401–406. [Google Scholar]
  9. Bonin-Font, F.; Ortiz, A.; Oliver, G. Visual Navigation for Mobile Robots: A Survey. J. Intell. Robot. Syst. 2008, 53, 263–296. [Google Scholar] [CrossRef]
  10. Ever, Y.K. Using simplified swarm optimization on path planning for intelligent mobile robot. Procedia Comput. Sci. 2017, 120, 83–90. [Google Scholar] [CrossRef]
  11. Hu, X.; Chen, L.; Tang, B.; Cao, D.; He, H. Dynamic path planning for autonomous driving on various roads with avoidance of static and moving obstacles. Mech. Syst. Signal Process. 2018, 100, 482–500. [Google Scholar] [CrossRef]
  12. Mei, Z.; Chen, Y.; Jiang, M.; Wu, H.; Cheng, L. Mobile Robots Path Planning Based on Dynamic Movement Primitives Library. In Proceedings of the 2017 36th Chinese Control Conference (CCC), Dalian, China, 26–28 July 2017. [Google Scholar] [CrossRef]
  13. Fox, D.; Burgard, W.; Thrun, S. The dynamic window approach to collision avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef] [Green Version]
  14. Borenstein, J.; Koren, Y. The vector field histogram-fast obstacle avoidance for mobile robots. IEEE Trans. Robot. Autom. 1991, 7, 278–288. [Google Scholar] [CrossRef] [Green Version]
  15. Buniyamin, N.; Ngah, W.A.J.W.; Mohamad, Z. PointsBug versus TangentBug algorithm, a performance comparison in unknown static environment. In Proceedings of the 2014 IEEE Sensors Applications Symposium (SAS), Queenstown, New Zealand, 17 April 2014; pp. 278–282. [Google Scholar]
  16. Adiyatov, O.; Varol, H.A. Rapidly-exploring random tree based memory efficient motion planning. In Proceedings of the 2013 IEEE International Conference on Mechatronics and Automation, Takamatsu, Japan, 4–7 August 2013; pp. 354–359. [Google Scholar]
  17. Aravindan, A.; Zaheer, S.; Gulrez, T. An integrated approach for path planning and control for autonomous mobile robots. In Proceedings of the 2016 International Conference on Next Generation Intelligent Systems (ICNGIS), Kottayam, India, 1–3 September 2016; pp. 1–6. [Google Scholar]
  18. Wang, W.J.; Hsu, T.M.; Wu, T.S. The improved pure pursuit algorithm for autonomous driving advanced system. In Proceedings of the 2017 IEEE 10th International Workshop on Computational Intelligence and Applications (IWCIA), Hiroshima, Japan, 11–12 November 2017; pp. 33–38. [Google Scholar]
  19. Corke, P. Robotics, Vision and Control: Fundamental Algorithms In MATLAB® Second, Completely Revised, Extended and Updated Edition, 2nd ed.; Springer International Publishing AG: Gewerbestrasse, Switzerland, 2011. [Google Scholar]
  20. Heller, C.; Yaesh, I. Proportional Navigation with integral action. In Proceedings of the Melecon 2010—2010 15th IEEE Mediterranean Electrotechnical Conference, Valletta, Malta, 26–28 April 2010; pp. 1546–1550. [Google Scholar]
  21. Sebi, S.A.; Sunny, D. Obstacle Avoidance in Mobile Robotic Sensors and Establishing Connection. Procedia Technol. 2016, 25, 364–371. [Google Scholar] [CrossRef] [Green Version]
  22. Peng, Y.; Qu, D.; Zhong, Y.; Xie, S.; Luo, J.; Gu, J. The obstacle detection and obstacle avoidance algorithm based on 2-D lidar. In Proceedings of the 2015 IEEE International Conference on Information and Automation, Lijiang, China, 8–10 August 2015; pp. 1648–1653. [Google Scholar]
  23. Catapang, A.N.; Ramos, M. Obstacle detection using a 2D LIDAR system for an Autonomous Vehicle. In Proceedings of the 2016 6th IEEE International Conference on Control System, Computing and Engineering (ICCSCE), Batu Ferringhi, Malaysia, 25–27 November 2016; pp. 441–445. [Google Scholar]
  24. Lee, D.; Lu, Y.; Kang, T.; Choi, I.; Lim, M. 3D vision based local obstacle avoidance method for humanoid robot. In Proceedings of the 2012 12th International Conference on Control, Automation and Systems, JeJu Island, Korea, 17–21 October 2012; pp. 473–475. [Google Scholar]
  25. Amin, N.; Borschbach, M. Quality of obstacle distance measurement using Ultrasonic sensor and precision of two Computer Vision-based obstacle detection approaches. In Proceedings of the 2015 International Conference on Smart Sensors and Systems (IC-SSS), Bangalore, India, 21–23 December 2015; pp. 1–6. [Google Scholar]
  26. Martínez, M.; Martínez, J.; Morales, J. Motion Detection from Mobile Robots with Fuzzy Threshold Selection in Consecutive 2D Laser Scans. Electronics 2015, 4, 82–93. [Google Scholar] [CrossRef] [Green Version]
  27. Wooten, J.; Bevly, D.; Hung, J. Piezoelectric Polymer-Based Collision Detection Sensor for Robotic Applications. Electronics 2015, 4, 204–220. [Google Scholar] [CrossRef] [Green Version]
Figure 1. Autonomous guided vehicle (AGV) and obstacle on a plane.
Figure 1. Autonomous guided vehicle (AGV) and obstacle on a plane.
Electronics 08 00159 g001
Figure 2. Distance between the object and AGV.
Figure 2. Distance between the object and AGV.
Electronics 08 00159 g002
Figure 3. The correction of Figure 2.
Figure 3. The correction of Figure 2.
Electronics 08 00159 g003
Figure 4. AGV dynamical behavior.
Figure 4. AGV dynamical behavior.
Electronics 08 00159 g004
Figure 5. Velocities in the front axle.
Figure 5. Velocities in the front axle.
Electronics 08 00159 g005
Figure 6. Scenario representation.
Figure 6. Scenario representation.
Electronics 08 00159 g006
Figure 7. Block Diagram.
Figure 7. Block Diagram.
Electronics 08 00159 g007
Figure 8. AGV Scenario.
Figure 8. AGV Scenario.
Electronics 08 00159 g008
Figure 9. AGV Trajectory.
Figure 9. AGV Trajectory.
Electronics 08 00159 g009
Figure 10. Following error.
Figure 10. Following error.
Electronics 08 00159 g010
Figure 11. AGV trajectory with different Kh values.
Figure 11. AGV trajectory with different Kh values.
Electronics 08 00159 g011
Figure 12. Velocity Adaption.
Figure 12. Velocity Adaption.
Electronics 08 00159 g012
Figure 13. Comparison scenario.
Figure 13. Comparison scenario.
Electronics 08 00159 g013
Figure 14. Both algorithm executions with the same conditions. (a) Dynamic window approach (DWA) trajectory execution and (b) proposed obstacle avoidance (POA) trajectory execution.
Figure 14. Both algorithm executions with the same conditions. (a) Dynamic window approach (DWA) trajectory execution and (b) proposed obstacle avoidance (POA) trajectory execution.
Electronics 08 00159 g014
Figure 15. DWA different instant captured figures from the trajectory. (a) First time, (b) second time, (c) third time, and (d) fourth time.
Figure 15. DWA different instant captured figures from the trajectory. (a) First time, (b) second time, (c) third time, and (d) fourth time.
Electronics 08 00159 g015
Figure 16. POA different instant captured figures from the trajectory. (a) first time, (b) second time, (c) third time, and (d) fourth time.
Figure 16. POA different instant captured figures from the trajectory. (a) first time, (b) second time, (c) third time, and (d) fourth time.
Electronics 08 00159 g016aElectronics 08 00159 g016b
Figure 17. POA worst case: (a) DWA trajectory for POA worst case, and (b) POA worst trajectory.
Figure 17. POA worst case: (a) DWA trajectory for POA worst case, and (b) POA worst trajectory.
Electronics 08 00159 g017
Figure 18. DWA worst case: (a) DWA worst trajectory and (b) POA trajectory for DWA worst case.
Figure 18. DWA worst case: (a) DWA worst trajectory and (b) POA trajectory for DWA worst case.
Electronics 08 00159 g018
Table 1. Terms and Parameters.
Table 1. Terms and Parameters.
NameDescription
e r r o r (m)Gap between AGV and target
V a g v (m/s)Speed setpoint
K v   ( s 1 ) Proportional constant for speed
K h (rad/m)Proportional constant for steering
γ (rad)Steering setpoint
θ (rad)AGV Rotation
( x ,   y , θ ) (m, m, rad)Target POSE
D o b s (m)Distance to the obstacle
D t a r g e t (m)Distance between the AGV and target
P o b s (m)Obstacle position
P a g v (m)AGV position
V I (m/s)Left wheel speed
V D (m/s)Right wheel speed
V c (m/s)Speed in the middle of the motorized axel
G ( V a g v , γ ˙ ) DWA optimization function
heading ( V a g v , γ ˙ ) Gap between AGV and goal for each trajectory
d i s t ( V a g v , γ ˙ ) Distance to the obstacle for each trajectory
v e l ( V a g v , γ ˙ ) The speed of each trajectory
POSEAGV position and orientation
AGVAutonomous guided vehicle
POAProposed obstacle avoidance
DWADynamic window approach
Table 2. Variables and Constant.
Table 2. Variables and Constant.
NameDescriptionConstant Value
K h (rad/m)Proportional constant for steering0.9
K v   ( s 1 ) Proportional constant for speed0.9
L i d a r m a x r a n g e (m)Lidar maximum range10
α (m)Security distance0.5
β Intensity of the avoid function0.5
μ Intensity of the speed function0.5
δ ,   φ , δ and   φ Constants for Sigmoid functions δ =   δ = 1 ;
φ =   φ = 0.5
L (m)Distance between axles1.8
b (m)Axle distance0.2
σ D , α D ,   β D and γ D DWA configurable constants σ D = 0.1 ;   α D = 0.2   ;
β D = 0.1 ; γ D = 3.0
Table 3. Analytics Results.
Table 3. Analytics Results.
TestStart Pose (m)AlgorithmOdometer (m) min   D o b s   ( m ) Toal   Time   ( s ) Mean Speed (m/s)Speed Arriving at Goal (m/s)
1(0,0,0)POA43.850.8047.550.960.36
DWA36.422.0035.450.920.81
2(0,1,0)POA41.450.5845.650.940.36
DWA36.432.0035.50.910.8
3(0,2,0)POA25.290.3422.950.930.36
DWA36.342.0035.40.910.8
4(0,3,0)POA24.850.5222.450.930.36
DWA36.212.0035.250.910.81
5(0,4,0)POA24.500.6722.150.930.36
DWA36.081.9435.10.910.81
6(0,5,0)POA24.300.7721.90.930.36
DWA36.411.8435.450.910.81
7(0,6,0)POA24.180.7921.80.920.36
DWA36.881.7835.90.910.82
8(0,7,0)POA24.160.7121.850.930.36
DWA36.941.8635.950.910.83
9(0,8,0)POA24.290.5022.050.930.36
DWA24.210.5439.650.510.82
10(0,9,0)POA24.650.5022.60.930.35
DWA24.050.7132.450.620.81
11(0,10,0)POA24.910.9624.50.930.33
DWA28.671.227.60.890.81
12(0,11,0)POA23.740.521.40.930.35
DWA28.601.1427.550.90.8
13(0,12,0)POA23.620.6721.20.930.36
DWA28.371.0427.350.890.79
14(0,13,0)POA23.740.5721.300.930.36
DWA28.170.9027.10.890.8
15(0,14,0)POA24.560.524.150.850.23
DWA24.631.624.150.850.81
16(0,15,0)POA25.350.524.200.80.16
DWA25.171.8224.60.860.81
17(0,16,0)POA25.940.524.40.930.33
DWA25.661.9724.850.870.82
18(0,17,0)POA26.540.525.550.930.36
DWA26.181.925.050.880.82
19(0,18,0)POA27.750.527.250.930.36
DWA26.381.3325.250.880.82
20(0,19,0)POA27.680.7526.70.930.36
DWA25.510.6925.30.850.82

Share and Cite

MDPI and ACS Style

Teso-Fz-Betoño, D.; Zulueta, E.; Fernandez-Gamiz, U.; Aramendia, I.; Uriarte, I. A Free Navigation of an AGV to a Non-Static Target with Obstacle Avoidance. Electronics 2019, 8, 159. https://doi.org/10.3390/electronics8020159

AMA Style

Teso-Fz-Betoño D, Zulueta E, Fernandez-Gamiz U, Aramendia I, Uriarte I. A Free Navigation of an AGV to a Non-Static Target with Obstacle Avoidance. Electronics. 2019; 8(2):159. https://doi.org/10.3390/electronics8020159

Chicago/Turabian Style

Teso-Fz-Betoño, Daniel, Ekaitz Zulueta, Unai Fernandez-Gamiz, Iñigo Aramendia, and Irantzu Uriarte. 2019. "A Free Navigation of an AGV to a Non-Static Target with Obstacle Avoidance" Electronics 8, no. 2: 159. https://doi.org/10.3390/electronics8020159

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