Conference PaperPDF Available

A Behavior-Based Path Planning for Autonomous Vehicle

Authors:

Abstract and Figures

The path planning is one of the key issues of autonomous vehicle. In this paper, a behavior-based method is used for path planning. This method can manage complexity environment and is easy to design and test behaviors. An autonomous electric vehicle is tested in a driving course including the behaviors of road following, turning, obstacle avoidance and emergency braking. The test results show that the path planning algorithm can run in a real-time, while the unknown obstacles can be avoided and the autonomous vehicle can be driven toward the destination in a smooth path and continuous motion.
Content may be subject to copyright.
A Behavior-Based Path Planning for Autonomous
Vehicle
CaiJing Xiu and Hui Chen
School of Automotive Studies, Tongji University, 1239 Siping Road,
Shanghai 200092, China
xcj2_11@163.com
hui-chen@tongji.edu.cn
Abstract. The path planning is one of the key issues of autonomous vehicle. In
this paper, a behavior-based method is used for path planning. This method can
manage complexity environment and is easy to design and test behaviors. An
autonomous electric vehicle is tested in a driving course including the behaviors
of road following, turning, obstacle avoidance and emergency braking. The test
results show that the path planning algorithm can run in a real-time, while the
unknown obstacles can be avoided and the autonomous vehicle can be driven
toward the destination in a smooth path and continuous motion.
Keywords: Autonomous vehicle, Driver behavior characteristics, Path planning,
Behavior-based
1 Introduction
Autonomous vehicle becomes a hot research topic due to the demand of the intelligent
transportation systems (ITS) and the military applications in the recent decades, while
the path planning is one of the key issues of the vehicle. The path planning can be
divided into the global path planning or navigation with fully known environmental
information and the local path planning with uncertain environmental information.
Goal-based path planning should avoid obstacles in a dynamic environment and reach
the destination automatically. In the study of path planning, a top-down traditional
method consists of the modules of sensing, modeling, planning and action. This
method is difficult to establish an accurate map of environment model, so it is difficult
to cope with real-time dynamic environment especially urban environment [1]. The
traditional method based on artificial potential field (APF) is improved for its
disadvantages such as local minimum [2][3][4], but APF does not consider some
constraints or regulations of road and traffic, such as stop line and intersection. It
means that APF can not be used to deal with all traffic in urban environment.
Intelligent control methods, such as fuzzy control [5][6], neural networks[7],
swarm[8][9]and so on, are applied in the study of path planning, but most of them are
remained in simulation study or used in specific unstructured environment.
Supported by Tongji University, Shanghai 200092, hina, TRW Automotive R&D
(Shanghai) Co., Ltd. and Science and Technology Commission of Shanghai
Municipality(07dz05901)
It can be seen that the current path planning methods have the disadvantages mainly in
real-time performance, universal property and flexibility for different traffic conditions,
especially for urban environment. In consideration of the above issues, the
behavior-based path planning is applied for autonomous vehicle in this paper. The
behavior is decomposed into a series of relatively independent small behaviors and the
behavior decision decides the behavior of autonomous vehicle by the environmental
characteristics [10][11].
2 Architecture of Autonomous Vehicle
In the process of driving, the structure of the driver's brain activity can be divided into
four layers: destination planning, behavior decision, behavior planning and operation
control [12], as showed in Fig.1. Destination planning layer is the first activity of the
driver to be carried out according to current vehicle status (including the location and
pose), driving destinations and pre-stored road map. It is global path planning of
autonomous vehicle related to all possible routes from the current status to destination
location considering some constrains such as shortcut, optimal time and so on. A series
of sub-goals are outputted from this layer [12]. Behavior decision layer is carried out
based on the environment characteristics, including vehicle status, traffic rules and
other information in the memory in order to determine the vehicle's driving behavior.
Behavior plan layer is the planning of driving trajectory and vehicle speed according to
driving behavior which is outputted by behavior decision layer. Operational control
layer is the operation of vehicle driving, braking, steeringthat istracking vehicle
trajectory which is given by behavior planning layer.
Fig.1. Driver's Thinking Layer
From the view point of controlling, the vehicle is the controlled object, the driver is the
sensor and controller, while the road and traffic regulations are the constraints of the
system in the process of driving. Driving safety is the basic requirements of the system.
From the above analysis, it can be found that the design target of an autonomous
vehicle is to replace the driver by the sensors and controllers, and to meet the
requirements of various constraints and conditions.
The ultimate goal of autonomous vehicles is to replace the driver from the closed-loop
control system of "driver - vehicle - road". Autonomous vehicle control system showed
in Fig.2 consists of four parts in this article: path planning, vehicle control that is the
trajectory and speed tracking, vehicle and environment. The path planning of this
closed-loop control system is studied in this paper.
Fig.2. Closed-Loop Control System of Autonomous Vehicle
3 Design of Path Planning Controller
The behavior-based planning method is applied to manipulate the unmanned vehicles
in uncertain environmental information. Behavior decision is made at each sampling
time according to real-time sensor data, the results of global and local path planning,
the distance and relative velocity between the autonomous vehicle and obstacles.
Autonomous vehicle behaviors are classified into road following, turning, obstacle
avoidance, emergency braking, ACC, merging into traffic flow, intersection crossing
and so on. In this paper, the first four behaviors of road following, turning, obstacle
avoidance and emergency braking are discussed.
3.1 Road following
When there is no obstacle or the distance between autonomous vehicle and obstacle is
greater than a safe distance, the road following behavior is triggered.
The control algorithm of road following behavior is based on preview following
theory [13] combined with PID control. The control model is shown in Fig.3.
Fig.3. Road Following Control Model
In this control model, V is the velocity of autonomous vehicle, (X,Y) is the current
coordinates of autonomous vehicle, they are the input of controller system. The
preview distance is given by the equation: S = K * V, while K is a proportional
coefficient and V is the velocity of autonomous vehicle. Steering angle is calculated
according to the lateral deviation between vehicle current coordinates and preview
point coordinates. The vehicle constrain module is the vehicle dynamics and
kinematics constraints such as the maximum steering angle and steering angular
velocity, etc.
3.2 Turning behavior
When the autonomous vehicle encounters an intersection, turning behavior is
triggered. Because of the vehicle dynamics and kinematics constraints, the curvature
of tracking of autonomous vehicle must be bounded and continuous, and the
derivative of curvature is also bounded. Therefore, behavioral strategy of turning is
calculated by polar polynomial of Nelson [14] [15].
General Nelson polarity polynomial expression is:
()
2345
012345
raaaaaa
ϕ
ϕϕ ϕ ϕ ϕ
=+++++
1
r is the polar radius,
ϕ
is the polar angle, i
a(i=1,2……)is polynomial coefficients,
they will be given in the following equation (4).
The constraint of location, slope '
r and curvature
κ
are:
,0,0 0
,0,0
rRr
rRr
κϕ
κϕ
=== =
=== =Φ
2
As the curvature of the path is:
()
()
22
3
22
2
2rrrr
rr
κϕ
′′
+−
=
+
dr
rd
ϕ
=
2
2
dr
rd
′′ =
3
From equations of (1) (2) (3), the equation (4) can be obtained.
0
1
2
3
42
5
0
2
2
0
aR
a
R
a
R
a
R
a
a
=
=
=
=−
Φ
=
Φ
=
4
To substitute the parameters of equation (1by equation (4), the expression will be:
()
23 4
2
122
rR
ϕϕ ϕ
ϕ
⎛⎞
=++
⎜⎟
ΦΦ
⎝⎠
5
Fig.4. Turning Control Model
The control model is shown in Figure4. R is maximum turning radius when turns,
road angle (the Φ in the formula) is the angle between the current road and the next
driving road of autonomous vehicle, LOOR is an sign from global path planning that
inform turn right or left. Angle calculation subsystem calculated front wheel angle by
equation: angle=arctan(L/r), L is the length of autonomous vehicle, slip angle is
ignored in this equation.
3. 3 Obstacle Avoidance
When the distance between autonomous vehicle and the obstacle is less than safe
distance, the obstacle avoiding behavior is triggered. Obstacle avoidance behavior is
achieved by an improved artificial potential field method.
In the structured environment, the road boundary can be considered as a repulsive
force field. There is no target point defined in the traditional artificial potential field
method. In this paper, the distance between autonomous vehicle and target point is
considered in the repulsive potential field [2][3].
Gravitational potential function is follows:
2
at goal
1
U(X)= k(X-X )
2 6
K is the location gain coefficient, goal
(X-X )is the distance between autonomous
vehicle and target point, the corresponding attractive potential field is the negative
gradient of target point.
()-( )
at
g
oal
FX kXX=−
uv 7
Improved repulsive potential field function is as following
2
re goal o
oo
o
111 111
U (X)= ( - )+ ( - )(X-X )
22
0 >
η
ηρρ
ρρ ρρ
ρ
ρ
8
η
is the location gain coefficient of repulsion,
ρ
is the distance between autonomous
vehicle and obstacle, o
ρ
is the safety threshold of autonomous vehicle. When the
distance of autonomous vehicle and obstacle is greater than the safety threshold, and
the repulsive function is zero. Repulsion function is obtained by following equation:
2
goal o
22
oo
o
11 1 11 1
(X)= ( - ) + ( - ) (X-X )
0 >
re
F
η
ηρρ
ρρ ρ ρρ ρ
ρ
ρ
uv
9
The force of the autonomous vehicle is:
sum at re
FF F=+
uv uv u u v 10
Fig.5. Sensor Fusion
Figure5 is the input of APF method,(Xob,Yob) is the obstacle coordinate that is given
by processing of radar data;(Xgo,Ygo) is the goal point coordinate that is given by
processing of camera data;(X,Y) is the autonomous vehicle coordinate that is given by
GPS. goal
(X-X ) and
ρ
will be known with the formula of the Length of the line
between two points. Then the Fre and Fat are ensured, because the input of
autonomous vehicle must be steering angle, according to the orientation of
autonomous vehicle, Fre and Fat will be divided into two pitch Fx and Fy, and the
steering angle is calculated by the following formula: angle=
arctan( / )Fy Fx
∑∑. Obstacle avoidance control Model is shown in Fig.6.
Autonomous vehicle will avoid the obstacles when the front obstacle hinder the travel
of autonomous vehicle and meet road constraint according to this method.
Fig.6. Avoid Obstacle Model
3.4 Emergency Braking Behavior
When the autonomous vehicle can not avoid collision by change the steering and
deceleration, emergency brake behavior is triggered.
4 Experiment
In order to verify the behavior-based path planning algorithm, a real vehicle
experiment is performed.
4.1 Experiment Condition
The autonomous electric vehicle shown in Fig.7 drives along a rectangular route
while a static or moving obstacle will emerge randomly. The vehicle speed is
controlled at 10km/h for this experiment. The environment perception sensors are
lidar, camera, GPS and so on.
Fig.7. Experiment Platform
4.2 Experiment Result
The trajectory of autonomous vehicle is shown in Figure 9. According to the safety
threshold, safety threshold is calculated as S = K * V, while the coefficient K is
related with the dynamics of vehicle and the communication speed of sensor, and is
set up as K = 8. When obstacles emerge, emergency braking behavior or collision
avoiding behavior will be carried out.
Fig.8. Experiment Tracking
5 Conclusions
In this paper, a behavior-based path planning method is applied for autonomous
electric vehicle. The experiment results show, 1) The applied path planning method is
effective for a real-time dynamic environment. 2) The behavior decision can perform a
correct behavior selection only with the information of vehicle status and surrounding
environment characteristics. The flexibility and real-time performance of the control
system is ensured. 3) Driving behaviors can be successfully decomposed into several
elemental behaviors. It shows the applied path planning method could be adapted to an
urban environment with complex driving behaviors. The further experiment studies
will be performed to verify the adaptability of urban driving condition.
References
1. YiBin Zhang,CaiHong Zhang, “The Study of Mobile Robot Path Planning in Uncertain
Enviroment”, Journal of Hangzhou Electronic Science and Technology University,2005
2. WANG Meng,WANG Xiao-rong, “Study of local path planning of mobile robot based on
improved artificial potential field method”, Computer Engineering and Design,2008
3. SHEN Kui-hua,TAN Yue-gang, “A Method Solving the Local Minimization Problem of
Artificial Potential Field”,Journal of Wuhan University of Technology,2005
4. David Clinton Conner“sensor fusion,navigation,and control of autonomous vehicles”,
Virginia Polytechnic Institute and State University, Thesis for the degree of Master.
5. Neil Eugene Hodge and Mohamed B. Trabia,“steering fuzzy logic controller for an
autonomous vehicle”, Proceedings of the 1999 IEEE International Conference on Robotics
& Automation.
6. EI Hajjaji,Oulasine,“modeling human vehicle driving by fuzzy logic for standardized ISO
double lane change maneuver”, Proceedings of the 2001 IEEE Symposium on Robot and
Human Interactive Communication.
7. Istvan Engedy,Gabor Horvath “Artificial Neural Network based Mobile Robot
Navigation” 2009 IEEE International Symposium on Intelligent Signal Processing
8. Sheetal Doctor,Ganesh K.Venayagamoorthy,“Unmanned Vehicle Navigation Using Swarm
Intelligence”2004 IEEE
9. Alejandro Ramirez-Serrano,Giovanni C.Pettinaro,“Navigation of Unmanned Vehicles
Using a Swarm of Intelligent Dynamic Landmarks”2005 IEEE
10. D. Langer, J. K. Rosenblatt, and M. Hebert, “A Behavior-Based System For Off-Road
Navigation” The Robotics Institute Carnegie Mellon University
11. Tobias Gindele, Daniel Jagszent, Design of the Planer of Team AnnieWAY’s
Autonomous Vehicle Used in the DARPA Urban Challenge 2007 2008 IEEE Intelligent
Vehicles Symposium.
12. Hangen He, “The Study of the Improvement and Technology of Intelligent Vehicle”
Defense Technology university.
13. GAO Zhen-hai,GUAN Hsin,GUO Kong-hui.Driver directional control model and the
application in the research of intelligent vehicle[J].China Journal of Highway and
Transport,2000,13(3).
14. W. Nelson, Continuous-Curvature Paths for Autonomous Vehicles, IEEE Int. Conf. on
Robotics and Automation, May 1989, Scotsdale, Ariz.,vol.3, pp.1260-1264,1989
15. O. Pinchard, A. Liegeois and F. Pougnet, Generalized polar polynomials for vehicle path
generation with dynamic constraints, In Proc. of the IEEE Int. Conf. on Robotics and
Automation, volume 1, pages 915–920, Minneapolis, MN (US), April 1996
... Most dispatch path planning techniques focus on problems where only one aircraft/traction system is involved. A recent review paper [4] categorizes related techniques into five kinds, i.e., Dijkstra's algorithms [5,6,7] , improved A* algorithms [8,9,10] , behavior dynamics based algorithms [10,11] , intelligent search methods [12,13] and optimal control based methods [14,15] . The above five kinds of techniques can be further divided into two groups, i.e., geometric methods (including the first three ones) and trajectory planning methods (including the last one), according to whether the kinematics are considered. ...
... However, during the actual trajectory tracking process, external safe 2R disturbances may drive the dispatch system deviate from the reference trajectory and thereby lead to collision. Hence, we introducing the constraint in Eq. (11) to force the deviation keep within an acceptable range. ...
Article
Full-text available
Taxiing aircraft and towed aircraft with drawbar are two typical dispatch modes on the flight deck of aircraft carriers. In this paper, a novel hierarchical solution strategy, named as the Homogenization-Planning-Tracking (HPT) method, to solve cooperative autonomous motion control for heterogeneous carrier dispatch systems is developed. In the homogenization layer, any towed aircraft system involved in the sortie task is abstracted into a virtual taxiing aircraft. This layer transforms the heterogeneous systems into a homogeneous configuration. Then in the planning layer, a centralized optimal control problem is formulated for the homogeneous system. Compared with conducting the path planning directly with the original heterogeneous system, the homogenization layer contributes to reduce the dimension and nonlinearity of the formulated optimal control problem in the planning layer and consequently improves the robustness and efficiency of the solution process. Finally, in the tracking layer, a receding horizon controller is developed to track the reference trajectory obtained in the planning layer. To improve the tracking performance, multi-objective optimization techniques are implemented offline in advance to determine optimal weight parameters used in the tracking layer. Simulations demonstrate that smooth and collision-free cooperative trajectory can be generated efficiently in the planning phase. And robust trajectory tracking can be realized in the presence of external disturbances in the tracking phase. The developed HPT method provides a promising solution to the autonomous deck dispatch for unmanned carrier aircraft in the future.
... Many researchers have been dedicated to solve the automatic lane merge problem and one of the most common way is to build a hierarchical structure which consists of two layers: path planning and trajectory tracking. Many different types of curves have been used to represent the geometry of the path including Nelson polynomials [8], Bezier curves [9], [10], clothoids [11], polynomial spirals [12], spline curves [13], [14] and arcs [15]. ...
... These curves have some special characteristics which are required for smooth trajectory such as continuous acceleration profile. Most popular curves are Bezier curves (Zhao et al., 2011;Ma et al., 2012;Pérez et al., 2013), Spline curves (Hardy and Campbell, 2013;Kala and Warwick, 2013;Wang et al., 2011), polynomial spirals (Gu et al., 2013;McNaughton et al., 2011), Nelson polynomials (Xiu and Chen, 2010), arcs (Sun et al., 2014) and clothoids (Broggi et al., 2012). ...
Article
Autonomous vehicles (AVs) have now drawn significant attentions in academic and industrial research because of various advantages such as safety improvement, lower energy and fuel consumption, exploitation of road network, reduced traffic congestion and greater mobility. In critical decision making process during motion of an AV, intelligent motion planning takes an important and challenging role for obstacle avoidance, searching for the safest path to follow, generation of suitable behavior and comfortable trajectory generation by optimization while keeping road boundaries and traffic rules as important concerns. An AV should also be able to decide the safest behavior (such as overtaking in case of highway driving) at each moment during driving. The behavior planning techniques anticipate the behaviors of all traffic participants; then it reasonably decides the best and safest behavior for AV. For this highly challenging task, many different motion and behavior planning techniques for AVs have been developed over past few decades. The purpose of this paper is to present an exhaustive and critical review of these existing approaches on motion and behavior planning for AVs in terms of their feasibility, capability in handling dynamic constraints and obstacles, and optimality of motion for comfort. A critical evaluation of the existing behavior planning techniques highlighting their advantages, ability in handling of static and dynamic obstacles, vehicle constraints and limitations in operational environments has also been presented.
... Behavior dynamics-based method is originally developed for path planning problems for mobile robots 40,41 and recently applied to those of carrier aircraft. It is considered that moving towards the object and obstacle avoidance constitute the path planning behavior modes of carrier aircraft. ...
Article
Full-text available
As an important part in sortie/recovery process, the dispatch of carrier aircraft not only affects the sortie/recovery efficiency and safety, but also has severe influence on the carrier’s combat efficiency and the comprehensive support capability. Path planning is the key to improve the efficiency and safety during the dispatch process. The main purpose of this paper is to propose a comprehensive investigation of techniques and research progress for the carrier aircraft’s dispatch path planning on the deck. Three different dispatch modes of carrier aircraft and the corresponding modeling technologies are investigated, and the aircraft’s dispatch path planning techniques and algorithms have been classified into different classes. Moreover, their assumptions and drawbacks have been discussed for single aircraft and multiple aircraft. To make the research work more comprehensive, the corresponding tracking control methodologies are also discussed. Finally, due to the similarity of path planning problem between the carrier aircraft’s dispatch and those in other fields, this paper provides an exploratory prospect of the knowledge or method learned from other fields.
... However, their work did not consider costs of driving behaviors, and hence performs poorly in task-completion efficiency. Similarly, task planners in [22], [23], [24] have no interaction with the motion planner, and safety was not modeled in generating the driving behaviors. ...
Preprint
Full-text available
Autonomous vehicles need to plan at the task level to compute a sequence of symbolic actions, such as merging left and turning right, to fulfill people's service requests, where efficiency is the main concern. At the same time, the vehicles must compute continuous trajectories to perform actions at the motion level, where safety is the most important. Task-motion planning in autonomous driving faces the problem of maximizing task-level efficiency while ensuring motion-level safety. To this end, we develop algorithm Task-Motion Planning for Urban Driving (TMPUD) that, for the first time, enables the task and motion planners to communicate about the safety level of driving behaviors. TMPUD has been evaluated using a realistic urban driving simulation platform. Results suggest that TMPUD performs significantly better than competitive baselines from the literature in efficiency, while ensuring the safety of driving behaviors.
... Then, a best trajectory is selected by cost function optimization and a sequence of control inputs is provided to the actuator for following the trajectory by AV. Most popular curves are Bezier curves [39]- [40], Spline curves [41]- [43], polynomial spirals [38,44], Nelson polynomials [45], arcs [46], and clothoids [47]. ...
Article
Full-text available
Article
Full-text available
Extensive studies have been conducted on unmanned vehicle recently due to its bright prospect. However, few have studied the technology of driverless bus. In this paper, a path planning and navigation control system is designed for 12 meters length driverless electric bus. The global path planning is adopted by Dijkstra algorithm based on analysis tool of ArcGIS. For local planning, a triple-layer finite state machine is proposed to plan the driving maneuver, and it reduces computational complexity and improves driving effectiveness. Meanwhile, optimal trajectory is generated by curve fitting technique based on path planning and driving maneuver, which takes full account of the safety and kinetics for driverless bus. And the speed planning by expert rules are addressed to imitate an experienced driver. Furthermore, the trajectory tracking controller is devised by an adaptive rolling window. Moreover, a heading error compensation model and self-adaptive strategy of controller parameters are set up to improve the control precision. Finally, simulation by TruckSim and scenes experiments verify the validity and practicability of our proposed path planning and navigation control system for driverless bus.
Conference Paper
The ability of autonomous vehicles to successfully replace human drivers depends on their capability to plan safe, efficient and usable paths in dynamically evolving traffic scenarios. This challenge gets more difficult when the autonomous vehicle has to drive through complex scenarios such as intersections which demand interactive behaviour between vehicles. Many autonomous vehicle demonstrations over the last few decades have highlighted the limitations in the current state-of-the-art of path planning solutions. They have been found to be inefficient and sometimes unsafe when tackling interactively demanding scenarios. The generic path planning solutions consists of three planners, a “global path planner”, a “behaviour planner” and a “local path planner. In this paper we establish that the “behaviour planner” is the limitation of a successful path planning solution, after reviewing the individual planners and the associated solutions. In this paper a new adaptive tactical behaviour planner is proposed to overcome the limitations. This planner is motivated by how expert human drivers behave in interactive scenarios, and is made up of a three module architecture. The paper describes the individual modules, and also highlights how they play a part in the overall behaviour selection for the autonomous vehicle. The paper is concluded by a discussion on how this proposed planner generates safe and efficient behaviours in complex dynamic traffic scenarios by considering a case of a roundabout not controlled by traffic signals.
Conference Paper
Full-text available
This paper describes a dynamic artificial neural network based mobile robot motion and path planning system. The method is able to navigate a robot car on flat surface among static and moving obstacles, from any starting point to any endpoint. The motion controlling ANN is trained online with an extended backpropagation through time algorithm, which uses potential fields for obstacle avoidance. The paths of the moving obstacles are predicted with other ANNs for better obstacle avoidance. The method is presented through the realization of the navigation system of a mobile robot.
Conference Paper
Full-text available
Unmanned vehicles are used to explore physical areas where humans are unable to go due to different constraints. There have been various algorithms that have been used to perform this task. This paper explores swarm intelligence for searching a given problem space for a particular target(s). The work in this paper has two parts. In the first part, a set of randomized unmanned vehicles are deployed to locate a single target. In the second part, the randomized unmanned vehicles are deployed to locate various targets and are then converged at one of targets of a particular interest. Each of the targets carries transmits some information which draws the attention of the randomized unmanned vehicles to the target of interest. The Particle Swarm Optimization (PSO) has been applied for solving this problem. Results have shown that the PSO algorithm converges the unmanned vehicles to the target of particular interest successfully and quickly.
Article
To avoid the disadvantage of artificial potential field, a method was put forward to separate the region which will result in local minimization by some special points. The mobile robot will get the location of goal point by the difference of area between the region and the figures consisting of the goal point and the special points beforehand. When the goal point is outside of the region, the mobile robot can avoid entering into these regions and fall into local minimization for the limiting information.
Conference Paper
The paths followed by autonomously guided vehicles (AGVs) are generally made up of line and circular-arc segments. For most AGVs, the steering functions required to keep the position and heading of the cart continuously aligned with such paths have discontinuities at the line-arc-line transitions points, because the curvature of the path is discontinuous at these points. For applications where continuous-curvature paths are desired, two types of curves are proposed; polar polynomials in place of circular-arc segments, and Cartesian polynomials in place of arc-arc or arc-line-arc segments for lane change maneuvers. Both curves have computationally simple, closed-form expressions that provide continuous curvature and precise matching of the boundary conditions at the line-curve junctions on the paths. The use of these curves in place of circular arcs for the reference-path generator on an experimental AGV has improved its tracking accuracy during the following turns, particularly at higher speeds
Conference Paper
This paper reports on the behaviour decision and execution unit of AnnieWAY , an autonomous vehicle that is capable of driving through urban scenarios and that has successfully entered the finals of the DARPA Urban Challenge 2007 competition. Starting with a short description of the car and its major hardware components, we outline the underlying software structure and focus on the design of the behavior decision module. The selection of maneuvers necessary to accomplish the mission is conducted online via a concurrent hierarchical state machine that specifically ascertains behavior in accordance with California traffic rules. The states and transitions used to model a adequate behaviour are described. We conclude with a report of the results achieved during the competition.
Conference Paper
The work presented here describes a novel 3D navigation method for teams of unmanned vehicles using intelligent dynamic landmarks (IDLs). The technique allows robots to navigate in diverse structured and unstructured environments both indoor and outdoor avoiding typical disadvantages of traditional navigational techniques. Some robots comprising the team are considered as IDLs while others use such landmarks to accomplish their task. The proposed approach does not require any type of traditional external landmarks or any kind of environmental model. Instead, robots continuously perform direct measurements of their relative position with respect to neighboring robots with which they interchange relative position information to verify relative and global localization. Robots process the obtained information to generate ego-centric estimates of the relative position of other robots using an origami graph. The proposed technique allows the team's configurations to change according to the task to be performed and allows effective navigation even under robots' mechanical and/or sensor failures.
Conference Paper
A driver model based on fuzzy logic is presented which has been developed in the context of the SERA electronic manufacture collaboration. The basic idea behind the work is that the human uses his sensory perception and expert knowledge to predict the vehicle's future behavior for the next few seconds. We propose a fuzzy control system and an optimization algorithm allowing a wheeled vehicle to pass a standardized ISO double lane chicane trajectory. The driver model has been implemented and tested on a 605 Peugeot simulator and validated experimentally. The results obtained for the standardized ISO double lane change (Chicane test) are presented
Conference Paper
Autonomous vehicles can be used in variety of applications such as hazardous environment or intelligent highway system. Fuzzy logic seems to be an appropriate choice for this area. This paper proposes a fuzzy logic controller for steering an autonomous vehicle toward a target. The controller is divided into separate modules to mimic the way humans think while driving. One module drives the vehicle toward the target while another is used to avoid collision with obstacles. A separate module is designed to drive the vehicle through mazes. The last module adjusts the final orientation of the target. The paper contains several examples to demonstrate the interaction between the several modules of the controller