Autonomous Driving in Urban Environments: Boss and the Urban Challenge
←
→
Page content transcription
If your browser does not render page correctly, please read the page content below
Autonomous Driving in Urban Environments: Boss and the Urban Challenge • • • • • • • • • • • • • • • • • • • • • • • • • • • • • • • Chris Urmson, Joshua Anhalt, Drew Bagnell, Christopher Baker, Robert Bittner, M. N. Clark, John Dolan, Dave Duggins, Tugrul Galatali, Chris Geyer, Michele Gittleman, Sam Harbaugh, Martial Hebert, Thomas M. Howard, Sascha Kolski, Alonzo Kelly, Maxim Likhachev, Matt McNaughton, Nick Miller, Kevin Peterson, Brian Pilnick, Raj Rajkumar, Paul Rybski, Bryan Salesky, Young-Woo Seo, Sanjiv Singh, Jarrod Snider, Anthony Stentz, William “Red” Whittaker, Ziv Wolkowicki, and Jason Ziglar Carnegie Mellon University Pittsburgh, Pennsylvania 15213 e-mail: curmson@ri.cmu.edu Hong Bae, Thomas Brown, Daniel Demitrish, Bakhtiar Litkouhi, Jim Nickolaou, Varsha Sadekar, and Wende Zhang General Motors Research and Development Warren, Michigan 48090 Joshua Struble and Michael Taylor Caterpillar, Inc. Peoria, Illinois 61656 Michael Darms Continental AG Auburn Hills, Michigan 48326 Dave Ferguson Intel Research Pittsburgh, Pennsylvania 15213 Received 22 February 2008; accepted 19 June 2008 Journal of Field Robotics 25(8), 425–466 (2008) C 2008 Wiley Periodicals, Inc. Published online in Wiley InterScience (www.interscience.wiley.com). • DOI: 10.1002/rob.20255
426 • Journal of Field Robotics—2008 Boss is an autonomous vehicle that uses on-board sensors (global positioning system, lasers, radars, and cameras) to track other vehicles, detect static obstacles, and localize itself relative to a road model. A three-layer planning system combines mission, behav- ioral, and motion planning to drive in urban environments. The mission planning layer considers which street to take to achieve a mission goal. The behavioral layer determines when to change lanes and precedence at intersections and performs error recovery maneu- vers. The motion planning layer selects actions to avoid obstacles while making progress toward local goals. The system was developed from the ground up to address the require- ments of the DARPA Urban Challenge using a spiral system development process with a heavy emphasis on regular, regressive system testing. During the National Qualifica- tion Event and the 85-km Urban Challenge Final Event, Boss demonstrated some of its capabilities, qualifying first and winning the challenge. C 2008 Wiley Periodicals, Inc. 1. INTRODUCTION To compete in the challenge, teams had to pass a series of tests. The first was to provide a credible In 2003 the Defense Advanced Research Projects technical paper describing how they would imple- Agency (DARPA) announced the first Grand Chal- ment a safe and capable autonomous vehicle. Based lenge. The goal was to develop autonomous vehi- on these papers, 53 teams were given the opportu- cles capable of navigating desert trails and roads at nity to demonstrate firsthand for DARPA their ability high speeds. The competition was generated as a re- to navigate simple urban driving scenarios including sponse to a congressional mandate that a third of passing stopped cars and interacting appropriately U.S. military ground vehicles be unmanned by 2015. at intersections. After these events, the field was fur- Although there had been a series of ground vehi- ther narrowed to 36 teams who were invited to par- cle research programs, the consensus was that exist- ticipate in the National Qualification Event (NQE) in ing research programs would be unable to deliver Victorville, California. Of these teams, only 11 would the technology necessary to meet this goal (Commit- qualify for the Urban Challenge Final Event (UCFE). tee on Army Unmanned Ground Vehicle Technology, This article describes the algorithms and mech- 2002). DARPA decided to rally the field to meet this anism that make up Boss (see Figure 1), an au- need. tonomous vehicle capable of driving safely in traffic The first Grand Challenge was held in March at speeds up to 48 km/h. Boss is named after Charles 2004. Though no vehicle was able to complete the “Boss” Kettering, a luminary figure in the automotive challenge, a vehicle named Sandstorm went the far- industry, with inventions as wide ranging as the all- thest, setting a new benchmark for autonomous ca- electric starter for the automobile, the coolant Freon, pability and providing a template on how to win the and the premature-infant incubator. Boss was devel- challenge (Urmson et al., 2004). The next year, five ve- oped by the Tartan Racing Team, which was com- hicles were able to complete a similar challenge, with posed of students, staff, and researchers from sev- Stanley (Thrun et al., 2006) finishing minutes ahead eral entities, including Carnegie Mellon University, of Sandstorm and H1ghlander (Urmson et al., 2006) General Motors, Caterpillar, Continental, and Intel. to complete the 244-km race in a little under 7 h. This article begins by describing the autonomous After the success of the Grand Challenges, vehicle and sensors and then moves on to a discus- DARPA organized a third event: the Urban Chal- sion of the algorithms and approaches that enabled it lenge. The challenge, announced in April 2006, called to drive autonomously. for autonomous vehicles to drive 97 km through an The motion planning subsystem (described in urban environment, interacting with other moving Section 3) consists of two planners, each capable of vehicles and obeying the California Driver Hand- avoiding static and dynamic obstacles while achiev- book. Interest in the event was immense, with 89 ing a desired goal. Two broad scenarios are consid- teams from around the world registering interest in ered: structured driving (road following) and un- competing. The teams were a mix of industry and structured driving (maneuvering in parking lots). academics, all with enthusiasm for advancing au- For structured driving, a local planner generates tonomous vehicle capabilities. trajectories to avoid obstacles while remaining in its Journal of Field Robotics DOI 10.1002/rob
Urmson et al.: Autonomous Driving in Urban Environments: Boss and the Urban Challenge • 427 Figure 1. Boss, the autonomous Chevy Tahoe that won the 2007 DARPA Urban Challenge. lane. For unstructured driving, such as entering/ ner to solve based on the strategic information pro- exiting a parking lot, a planner with a four- vided by the mission planner. The behavioral subsys- dimensional search space (position, orientation, di- tem makes tactical decisions to execute the mission rection of travel) is used. Regardless of which plan- plan and handles error recovery when there are prob- ner is currently active, the result is a trajectory that, lems. The behavioral system is roughly divided into when executed by the vehicle controller, will safely three subcomponents: lane driving, intersection han- drive toward a goal. dling, and goal selection. The roles of the first two sub- The perception subsystem (described in components are self-explanatory. Goal selection is re- Section 4) processes and fuses data from Boss’s sponsible for distributing execution tasks to the other multiple sensors to provide a composite model of the behavioral components or the motion layer and for world to the rest of the system. The model consists selecting actions to handle error recovery. of three main parts: a static obstacle map, a list of The software infrastructure and tools that enable the moving vehicles in the world, and the location of the other subsystems are described in Section 7. The Boss relative to the road. software infrastructure provides the foundation upon The mission planner (described in Section 5) com- which the algorithms are implemented. Additionally, putes the cost of all possible routes to the next mission the infrastructure provides a toolbox of components checkpoint given knowledge of the road network. for online data logging, offline data log playback, and The mission planner reasons about the optimal path visualization utilities that aid developers in building to a particular checkpoint much as a human would and troubleshooting the system. A run-time execu- plan a route from his or her current position to a desti- tion framework is provided that wraps around algo- nation, such as a grocery store or gas station. The mis- rithms and provides interprocess communication, ac- sion planner compares routes based on knowledge cess to configurable parameters, a common clock, and of road blockages, the maximum legal speed limit, a host of other utilities. and the nominal time required to make one maneu- Testing and performance in the NQE and UCFE ver versus another. For example, a route that allows are described in Sections 8 and 9. During the develop- a higher overall speed but incorporates a U-turn may ment of Boss, the team put a significant emphasis on actually be slower than a route with a lower overall evaluating performance and finding weaknesses to speed but that does not require a U-turn. ensure that the vehicle would be ready for the Urban The behavioral system (described in Section 6) Challenge. During the qualifiers and final challenge, formulates a problem definition for the motion plan- Boss performed well, but made a few mistakes. Journal of Field Robotics DOI 10.1002/rob
428 • Journal of Field Robotics—2008 Despite these mistakes and a very capable field of nized through a custom pulse-per-second adaptor competitors, Boss qualified for the final event and board. won the Urban Challenge. Boss uses a combination of sensors to provide the redundancy and coverage necessary to navigate safely in an urban environment. Active sensing is 2. BOSS used predominantly, as can be seen in Table I. The de- Boss is a 2007 Chevrolet Tahoe modified for au- cision to emphasize active sensing was primarily due tonomous driving. Modifications were driven by the to the team’s skills and the belief that in the Urban need to provide computer control and also to support Challenge direct measurement of range and target safe and efficient testing of algorithms. Thus, modi- velocity was more important than getting richer, but fications can be classified into two categories: those more difficult to interpret, data from a vision system. for automating the vehicle and those that made test- The configuration of sensors on Boss is illustrated in ing either safer or easier. A commercial off-the-shelf Figure 2. One of the novel aspects of this sensor con- drive-by-wire system was integrated into Boss with figuration is the pair of pointable sensor pods located electric motors to turn the steering column, depress above the driver and front passenger doors. Each pod the brake pedal, and shift the transmission. The third- contains an ARS 300 radar and ISF 172 LIDAR. By row seats and cargo area were replaced with electron- pointing these pods, Boss can adjust its field of re- ics racks, the steering was modified to remove excess gard to cover crossroads that may not otherwise be compliance, and the brakes were replaced to allow observed by a fixed-sensor configuration. faster braking and reduce heating. Boss maintains normal human driving controls 3. MOTION PLANNING (steering wheel and brake and gas pedals) so that The motion planning layer is responsible for execut- a safety driver can quickly and easily take control ing the current motion goal issued from the behav- during testing. Boss has its original seats in addi- iors layer. This goal may be a location within a road tion to a custom center console with power and net- lane when performing nominal on-road driving, a lo- work outlets, which enable developers to power lap- cation within a zone when traversing through a zone, tops and other accessories, supporting longer and or any location in the environment when performing more productive testing. A welded tube roll cage error recovery. The motion planner constrains itself was also installed to protect human occupants in the based on the context of the goal to abide by the rules event of a collision or rollover during testing. For un- of the road. manned operation a safety radio is used to engage In all cases, the motion planner creates a path autonomous driving, pause, or disable the vehicle. toward the desired goal and then tracks this path Boss has two independent power buses. The by generating a set of candidate trajectories that fol- stock Tahoe power bus remains intact with its 12- low the path to various degrees and selecting from V dc battery and harnesses but with an upgraded this set the best trajectory according to an evaluation high-output alternator. An auxiliary 24-V dc power function. This evaluation function differs depending system provides power for the autonomy hardware. on the context but includes consideration of static The auxiliary system consists of a belt-driven alter- and dynamic obstacles, curbs, speed, curvature, and nator that charges a 24-V dc battery pack that is in- deviation from the path. The selected trajectory can verted to supply a 120-V ac bus. Shore power, in the then be directly executed by the vehicle. For more form of battery chargers, enables Boss to remain fully details on all aspects of the motion planner, see powered when in the shop with the engine off. Ther- Ferguson, Howard, and Likhachev (2008, submitted). mal control is maintained using the stock vehicle air- conditioning system. For computation, Boss uses a CompactPCI chas- 3.1. Trajectory Generation sis with 10 2.16-GHz Core2Duo processors, each A model-predictive trajectory generator originally with 2 GB of memory and a pair of gigabit Ether- presented in Howard and Kelly (2007) is responsible net ports. Each computer boots off of a 4-GB flash for generating dynamically feasible actions from an drive, reducing the likelihood of a disk failure. Two initial state x to a desired terminal state. In general, of the machines also mount 500-GB hard drives for this algorithm can be applied to solve the problem data logging. Each computer is also time synchro- of generating a set of parameterized controls u(p,x) Journal of Field Robotics DOI 10.1002/rob
Urmson et al.: Autonomous Driving in Urban Environments: Boss and the Urban Challenge • 429 Table I. Description of the sensors incorporated into Boss. Sensor Characteristics Applanix POS-LV 220/420 GPS/IMU (APLX) • Submeter accuracy with Omnistar VBS corrections • Tightly coupled inertial/GPS bridges GPS outages SICK LMS 291-S05/S14 LIDAR (LMS) • 180/90 deg × 0.9 deg FOV with 1/0.5-deg angular resolution • 80-m maximum range Velodyne HDL-64 LIDAR (HDL) • 360 × 26-deg FOV with 0.1-deg angular resolution • 70-m maximum range Continental ISF 172 LIDAR (ISF) • 12 × 3.2 deg FOV • 150-m maximum range IBEO Alasca XT LIDAR (XT) • 240 × 3.2 deg FOV • 300-m maximum range Continental ARS 300 Radar (ARS) • 60/17 deg × 3.2 deg FOV • 60-m/200-m maximum range Point Grey Firefly (PGF) • High-dynamic-range camera • 45-deg FOV Figure 2. The mounting location of sensors on the vehicle; refer to Table I for abbreviations used in this figure. that satisfy state constraints C(x) whose dynamics the target terminal state constraints and the integral can be expressed in the form of a set of differential of the model dynamics: equations f: xC = [xC yC θC ]T , (2) x· = f[x, u(p, x)]. (1) tf C(x) − xC − · p) dt = 0. x(x, (3) 0 To navigate urban environments, position and heading terminal state constraints are typically re- The fidelity of the vehicle model directly cor- quired to properly orient a vehicle along the road. relates to the effectiveness of a model-predictive The constraint equation xC is the difference between planning approach. The vehicle model describes Journal of Field Robotics DOI 10.1002/rob
430 • Journal of Field Robotics—2008 the mapping from control inputs to state response As described, the system retains three parameter- (changes in position, orientation, velocity, etc.). Se- ized freedoms: two curvature command spline knot lecting an appropriate parameterization of controls points (κ1 , κ2 ) and the trajectory length s. The duality is important because it defines the space over which of the trajectory length sf and time tf can be resolved the optimization is performed to satisfy the boundary by estimating the time that it takes to drive the en- state constraints. tire distance through the linear velocity profile. Time The vehicle model used for Boss combines a cur- was used for the independent variable for the linear vature limit (the minimum turning radius), a curva- velocity command function because of the simplicity ture rate limit (a function of the maximum speed at of computing profiles defined by accelerations (linear which the steering wheel can be turned), maximum ramp and trapezoidal profiles). Arc length was used acceleration and deceleration, and a model of the con- for the curvature command function because the tra- trol input latency. This model is then simulated using jectory shape is less dependent on the speed at which a fixed-timestep Euler integration to evaluate the con- trajectories are executed. straint equation. Given the three free parameters and the three The control inputs are described by two param- constraints in our system, we can use various opti- eterized functions: a time-based linear velocity func- mization techniques to solve for the parameter values tion vcmd and an arc-length-based curvature function that minimize our constraint equation. An initial es- κcmd : timate of the parameter values is defined using a precomputed approximate mapping from state space u(p, x) = [vcmd (p, t) + κcmd (p, s)]T . (4) to parameter space in a lookup table. The parame- ter estimates are iteratively modified by linearizing The linear velocity profile takes the form of a and inverting the differential equations describing constant profile, linear profile, linear ramp profile, the equations of motion. A correction factor is gen- or a trapezoidal profile (Figure 3). The local motion erated by taking the product of the inverted Jacobian planner selects the appropriate parameterization for and the boundary state constraint error. The Jacobian particular applications (such as parking and distance is model invariant because it is determined numeri- keeping). cally through central differences of simulated vehicle The response to the curvature command function actions: by the vehicle model defines the shape of the tra- tf jectory. The profile consists of three dependent pa- xF (p, x) = · p) dt, x(x, (6) rameters (κ0 , κ1 , and κ2 ) and the trajectory length sf . 0 A second-order spline profile was chosen because it C(x, p) = xC − xF (p, x), (7) contains enough degrees of freedom (four) to sat- isfy the boundary state constraints (three). The initial δC(x, p) −1 p = − C(x, p). (8) spline knot point κ0 is fixed during the optimization δp process to a value that generates a smooth or sharp tra- jectory and will be discussed later: The control parameters are modified until the residual of the boundary state constraints is within pfree = [κ1 κ2 sf ]T . (5) acceptable bounds or until the optimization diverges. Figure 3. Velocity profiles used by the trajectory generator. Journal of Field Robotics DOI 10.1002/rob
Urmson et al.: Autonomous Driving in Urban Environments: Boss and the Urban Challenge • 431 If the boundary state constraints are infeasible to reach given a particular parameterization (e.g., inside the minimum turning radius), the optimization is ex- pected to diverge. The resulting trajectory is returned as the best estimate and is evaluated by the motion planner. 3.2. On-Road Navigation During on-road navigation, the motion goal from the behavioral system is a location within a road lane. Figure 4. Smooth and sharp trajectories. The trajectory sets are generated to the same endpoints but differ in their The motion planner then attempts to generate a tra- initial commanded curvature. jectory that moves the vehicle toward this goal loca- tion in the desired lane. To do this, it first constructs a curve along the centerline of the desired lane. This represents the nominal path that the center of the ve- cles in the environment, as well as their distance from hicle should follow. This curve is then transformed the centerline path, their smoothness, and various into a path in rear-axle coordinates to be tracked by other metrics. The best trajectory according to these the motion planner. metrics is selected and executed by the vehicle. Be- To robustly follow the desired lane and to avoid cause the trajectory generator computes the feasibil- static and dynamic obstacles, the motion planner gen- ity of each trajectory using an accurate vehicle model, erates trajectories to a set of local goals derived from the selected trajectory can be directly executed by the the centerline path. The local goals are placed at a vehicle controller. fixed longitudinal distance down the centerline path Figure 5 provides an example of the local planner but vary in lateral offset from the path to provide sev- following a road lane. Figure 5(a) shows the vehicle eral options for the planner. The trajectory genera- navigating down a two-lane road (lane boundaries tion algorithm is used to compute dynamically fea- shown in blue, current curvature of the vehicle sible trajectories to these local goals. For each goal, shown in pink, minimum turning radius arcs shown two trajectories are generated: a smooth trajectory in white) with a vehicle in the oncoming lane. and a sharp trajectory. The smooth trajectory has the Figure 5(b) shows the extracted centerline path from initial curvature parameter fixed to the curvature of the desired lane (in red). Figure 5(c) shows a set of the forward-predicted vehicle state. The sharp tra- trajectories generated by the vehicle given its current jectory has the initial curvature parameter set to an state and the centerline path and lane boundaries. offset value from the forward-predicted vehicle state From this set of trajectories, a single trajectory is se- to produce a sharp initial action. The velocity pro- lected for execution, as discussed above. Figure 5(d) file used for each of these trajectories is computed shows the evaluation of one of these trajectories based on several factors, including the maximum ve- against both static and dynamic obstacles in the envi- locity bound given from the behavioral subsystem, ronment, and Figure 5(f) shows this trajectory being the speed limit of the current road segment, the maxi- selected for execution by the vehicle. mum velocity feasible given the curvature of the cen- terline path, and the desired velocity at the goal (e.g., zero if it is a stop line). 3.3. Zone Navigation Figure 4 provides an example of smooth and During zone navigation, the motion goal from behav- sharp trajectories (light and dark) generated to the iors is a pose within a zone (such as a parking spot). same goal poses. The smooth trajectories exhibit con- The motion planner attempts to generate a trajectory tinuous curvature control throughout; the sharp tra- that moves the vehicle toward this goal pose. How- jectories begin with a discontinuous jump in curva- ever, driving in unstructured environments, such as ture control, resulting in a sharp response from the zones, significantly differs from driving on roads. As vehicle. mentioned in the preceding section, when traveling The resulting trajectories are then evaluated on roads the desired lane implicitly provides a pre- against their proximity to static and dynamic obsta- ferred path for the vehicle (the centerline of the lane). Journal of Field Robotics DOI 10.1002/rob
432 • Journal of Field Robotics—2008 (a) (b) (c) (d) (e) (f) Figure 5. A single timeframe following a road lane from the DARPA Urban Challenge. Shown is the centerline path extracted from the lane (b), the trajectories generated to track this path (c), and the evaluation of one of these trajectories against both static and dynamic obstacles (d and e). In zones there are no driving lanes, and thus the time allows. At any point in time, Anytime D∗ pro- movement of the vehicle is far less constrained. vides a provable upper bound on the subotpimality To efficiently plan a smooth path to a distant goal of the plan. When new information concerning the pose in a zone, we use a lattice planner that searches environment is received (for instance, a new static or over vehicle position (x, y), orientation θ , and speed dynamic obstacle is observed), Anytime D∗ is able to v. The set of possible local maneuvers considered for efficiently repair its existing solution to account for each (x, y, θ, v) state in the planner’s search space is the new information. This repair process is expedited constructed offline using the same vehicle model as by performing the search in a backward direction, be- used in trajectory generation, so that it can be accu- cause in such a scenario, updated information in the rately executed by the vehicle. This planner searches vicinity of the vehicle affects a smaller portion of the in a backward direction, from the goal pose out into search space so that less repair is required. the zone, and generates a path consisting of a se- To scale to very large zones (up to 0.5 × 0.5 km), quence of feasible high-fidelity maneuvers that are the planner uses a multiresolution search and ac- collision-free with respect to the static obstacles ob- tion space. In the vicinity of the goal and vehicle, served in the environment. This path is also biased where very complex maneuvering may be required, away from undesirable areas within the environment, the search considers states of the vehicles with 32 such as curbs and locations in the vicinity of dynamic uniformly spaced orientations. In the areas that are obstacles. not in the vicinity of the goal or a vehicle, the search To efficiently generate complex plans over large, considers only the states of the vehicle with 16 uni- obstacle-laden environments, the planner relies on formly spaced orientations. It also uses a sparse set of an anytime, replanning search algorithm known as actions that allow the vehicle to transition between Anytime D∗ (Likhachev, Ferguson, Gordon, Stentz, & these states. Because coarse- and dense-resolution Thrun, 2005). Anytime D∗ quickly generates an ini- variants share the same dimensionality and, in par- tial, suboptimal plan for the vehicle and then im- ticular, have 16 orientations in common, they seam- proves the quality of this solution while deliberation lessly interface with each other, and the resulting Journal of Field Robotics DOI 10.1002/rob
Urmson et al.: Autonomous Driving in Urban Environments: Boss and the Urban Challenge • 433 Figure 6. Replanning when new information is received. As Boss navigates toward its desired parking spot (lattice path shown in red, trajectories to track path in various colors), it observes more of one of the adjacent vehicles and replans a path that brings it smoothly into the spot. solution paths overlapping both coarse and dense ar- terminate on the path. Each trajectory is in fact a con- eas of the space are smooth and feasible. catenation of two short trajectories, with the first of To ensure that a path is available for the vehicle the two short trajectories ending at an offset position as soon as it enters a zone, the lattice planner begins from the path and the second ending back on the planning for the first goal pose within the zone while path. By having all concatenated trajectories return the vehicle is still approaching the zone. By planning to the path, we significantly reduce the risk of having a path from the entry point of the zone in advance, the the vehicle move itself into a state that is difficult to vehicle can seamlessly transition into the zone with- leave. out needing to stop, even for very large and complex Figure 6 illustrates the tracking of the lattice plan zones. In a similar vein, when the vehicle is in a zone and the replanning capability of the lattice planner. traveling toward a parking spot, we have a second These images were taken from a parking task per- lattice planner computing a path from that spot to the formed during the NQE (the top-left image shows next desired location (e.g., the next parking spot to the zone in green and the neighboring roads in blue). reach or an exit of the zone). When the vehicle reaches The top-right image shows the initial path planned its intended parking spot, the vehicle then immedi- for the vehicle to enter the parking spot indicated by ately follows the path from this second planner, again the white triangle. Several of the other spots were oc- eliminating any time spent waiting for a plan to be cupied by other vehicles (shown as rectangles of var- generated. ious colors), with detected obstacles shown as red ar- The resulting plan is then tracked by the local eas. The trajectories generated to follow the path are planner in a similar manner to the paths extracted shown emanating from our vehicle. (Notice how each from road lanes. The motion planner generates a set trajectory consists of two sections, with the first leav- of trajectories that attempt to follow the plan while ing the path and the second returning to the path.) As also allowing for local maneuverability. However, in the vehicle gets closer to its intended spot, it observes contrast to when following lane paths, the trajecto- more of the vehicle parked in the right-most park- ries generated to follow the zone path all attempt to ing spot (bottom-left image). At this point, it realizes Journal of Field Robotics DOI 10.1002/rob
434 • Journal of Field Robotics—2008 that its current path is infeasible and replans a new path that has the vehicle perform a loop and pull in smoothly. This path was favored in terms of time over stopping and backing up to reposition. The lattice planner is flexible enough to be used in a large variety of cases that can occur during on- T x x, y , x, y , x , y T x x, y , v, a , , road and zone navigation. In particular, it is used dur- x x ing error recovery when navigating congested inter- (a) (b) sections, to perform difficult U-turns, and to get the vehicle back on track after emergency defensive driv- ing maneuvers. In such cases, the behaviors layer is- Figure 7. The two models used by the tracking system: a sues a goal pose (or set of poses) to the motion plan- reduced bicycle model with a fixed shape (a) and a point model without shape information (b). ner and indicates that it is in an error recovery mode. The motion planner then uses the lattice planner to generate a path to the set of goals, with the lattice planner determining during its planning which goal • Object identifiers are not guaranteed to be is easiest to reach. In these error recovery scenarios stable. A new identifier does not necessarily the lattice planner is biased to avoid areas that could mean that it is a new object. result in unsafe behavior (such as oncoming lanes • Well-defined and distinct tracking models are when on roads). used to maximize the use of information pro- vided by heterogeneous sensors. 4. PERCEPTION • Motion prediction exploits known road ge- ometry when possible. The perception system is responsible for providing • Sensor-specific algorithms are encapsulated a model of the world to the behavioral and motion in sensor-specific modules. planning subsystems. The model includes the mov- ing vehicles (represented as a list of tracked objects) Figure 7 shows the two tracking models used and static obstacles (represented in a regular grid) to describe object hypotheses. The box model repre- and localizing the vehicle relative to, and estimating sents a vehicle by using a simplified bicycle model the shape of, the roads it is driving on. (Kaempchen, Weiss, Schaefer, & Dietmayer, 2004) with a fixed length and width. The point model pro- 4.1. Moving Obstacle Detection and Tracking vides no estimate of extent of the obstacle and as- The moving obstacle detection and tracking subsys- sumes a constant-acceleration model (Darms, Rybski, tem provides a list of object hypotheses and their & Urmson, 2008a) with adaptive noise dependent on characteristics to the behavioral and motion planning the length and direction of the velocity vector. Provid- subsystems. The following design principles guided ing two potential tracking models enables the system the implementation: to represent the best model of tracked objects sup- ported by the data. The system is able to switch be- • No information about driving context is used tween these models as appropriate. inside the tracking algorithm. The system classifies object hypotheses as either • No explicit vehicle classification is per- moving or not moving and either observed moving or not formed. The tracking system provides observed moving, so that each hypothesis can be in one information only about the movement state of four possible states. The moving flag is set if the of object hypotheses. object currently has a velocity that is significantly dif- • Information about the existence of objects is ferent from zero. The observed moving flag is set once based on sensor information only. It is pos- the object has been moving for a significant amount sible for some objects to be predicted, but of time (on the order of 0.4 s) and is not cleared un- only for short time intervals, as a compensa- til the vehicle has been stopped for some larger sig- tion for known sensor parameters. Detection nificant amount of time (on the order of 10 s). The dropouts caused by noise, occlusions, and four states act as a well-defined interface to the other other artifacts must be handled elsewhere. software modules, enabling classes of tracked objects Journal of Field Robotics DOI 10.1002/rob
Urmson et al.: Autonomous Driving in Urban Environments: Boss and the Urban Challenge • 435 Object Hypothesis Set Fusion Layer Road World Model & Object Management Global Target Validation Instantaneous Map Estimation & Prediction RWM Checking Model Selection Global Classification Measurement Validated (Observations, Proposals, Features (Observations, Features Movement Observation) Sensor Layer Local Classification & Proposal Generation Association Local Target Validation Feature Extraction Figure 8. The moving obstacle detection and tracking system architecture. to be ignored in specific contexts (e.g., not observed a moving vehicle. The second step is performed via moving object hypotheses that are not fully on a road a general validation interface. The validation per- can be ignored for distance-keeping purposes, as they formed inside the fusion layer uses only non-sensor- likely represent vehicles parked at the side of the specific information. It performs checks against the road or other static obstacles (Darms, Baker, Rybski, road geometry and against an instantaneous obstacle & Urmson, 2008). map, which holds untracked three-dimensional (3D) Figure 8 illustrates the architecture of the track- information about any obstacles in the near range. ing system. It is divided into two layers, a sensor layer The result is a list of validated features that poten- and a fusion layer (Darms & Winner, 2005). For each tially originate from vehicles. sensor type (e.g., radar, scanning laser, etc.), a special- The validated features are associated with the ized sensor layer is implemented. For each physical predicted object hypotheses using a sensor-type- sensor on the robot a corresponding sensor layer in- specific association algorithm. Afterward, for each stance runs on the system. The architecture enables extracted feature (associated or not), multiple possi- new sensor types to be added to the system with ble interpretations as a box or point model are gen- minimal changes to the fusion layer, and other sen- erated using a sensor-type-specific heuristic, which sor modules, such as new physical sensors, can be takes the sensor characteristics into account [e.g., res- added without any modifications to source code. The olution, field of view (FOV), detection probabilities]. following paragraphs describe the path from sensor The compatibility of each generated interpretation raw data to a list of object hypotheses. with its associated prediction is computed. If an inter- Each time a sensor receives new raw data, its cor- pretation differs significantly, or if the feature could responding sensor layer instance requests a predic- not be associated, the sensor module initializes a new tion of the current set of object hypotheses from the object hypothesis. In case of an associated feature, a fusion layer. Features are extracted out of the mea- new hypothesis can replace the current model hy- sured raw data with the goal of finding all vehicles pothesis (box or point model). Note that for each fea- around the robot (e.g., edges from laser scanner data; ture, multiple new hypotheses can be generated. A MacLachlan, 2005). Artifacts caused by ground detec- set of new object hypotheses is called a proposal. tions or vegetation, for example, are suppressed by For each associated feature the interpretation that validating features in two steps. In the first step val- best fits the prediction is used to generate an observa- idation is performed with sensor-specific algorithms, tion. An observation holds all of the data necessary e.g., using the velocity measurements inside a radar to update the state estimation for the associated ob- module to distinguish a static ground return from ject hypothesis in the fusion layer. If no interpretation Journal of Field Robotics DOI 10.1002/rob
436 • Journal of Field Robotics—2008 Figure 9. The moving obstacle detection system predicts the motion of tracked vehicles. In parking lots (left) predictions are generated by extrapolating the tracking filter. For roads (right) vehicles are predicted to move along lanes. is compatible, then no observation is generated and ment observations that classify an object as moving only the proposal exists. As additional information (Darms et al., 2008). for each extracted feature becomes available, the sen- The result is an updated list of object hypothe- sor module can also provide a movement observa- ses that are accompanied by the classification of the tion. The movement observation tells the fusion layer movement state. For objects that are classified as whether an object is currently moving. This infor- moving and observed moving, a prediction of the mation is based only on sensor raw data (e.g., via state variables is made. The prediction is based on an evaluation of the velocity measurement inside the logical constraints for objects that are located on the radar module). road. At every point where a driver has a choice The proposals, observations, and movement ob- to change lanes (e.g., at intersections), multiple hy- servations are used inside the fusion layer to update potheses are generated. In zones (parking lots, for the object hypotheses list and the estimated object example), the prediction is solely based on the esti- states. First the best tracking model (box or point) mated states of the hypothesis (see Figure 9). is selected with a voting algorithm. The decision is based on the number and type of proposals provided from the different sensors (Darms, Rybski, & Urmson, 4.2. Static Obstacle Detection and Mapping 2008b). For objects that are located on roads, the road The static obstacle mapping system combines data shape is used to bias the decision. from the numerous scanning lasers on the vehicle Once the best model is determined, the state esti- to generate both instantaneous and temporally fil- mate is either updated with the observation provided tered obstacle maps. The instantaneous obstacle map by the sensor layer or the model for the object hy- is used in the validation of moving obstacle hypothe- pothesis is switched to the best alternative. For unas- ses. The temporally filtered maps are processed to re- sociated features, the best model of the proposal is move moving obstacles and are filtered to reduce the added to the current list of object hypotheses. With number of spurious obstacles appearing in the maps. the update process complete, object hypotheses that Whereas several algorithms were used to generate have not been observed for a certain amount of time obstacle maps, only the curb detection algorithm is are removed from the list. presented here. Finally, a classification of the movement state for Geometric features (curbs, berms, and bushes) each object hypothesis is carried out. It is based on the provide one source of information for determin- movement observations from the sensors and a statis- ing road shape in urban and off-road environments. tical test based on the estimated state variables. The Dense LIDAR data provide sufficient information to movement observations from sensors are prioritized generate accurate, long-range detection of these rel- over the statistical test, and movement observations evant geometric features. Algorithms to detect these that classify an object as not moving overrule move- features must be robust to the variation in features Journal of Field Robotics DOI 10.1002/rob
Urmson et al.: Autonomous Driving in Urban Environments: Boss and the Urban Challenge • 437 found across the many variants of curbs, berms, input signal within various sampling windows (Shih ditches, embankments, etc. The curb detection algo- & Tseng, 2005). Because each sampling window is rithm presented here exploits the Haar wavelet to half the size of the previous window, these windows deal with this variety. successively subdivide the signal into higher resolu- To detect curbs, we exploit two principle insights tion slopes or detail levels. into the LIDAR data to simplify detection. First, the The feature extraction step (see Figure 10) takes road surface is assumed to be relatively flat and the Haar coefficients, y, and considers them by win- slow changing, with road edges defined by observ- dow sizes, going from largest to smallest window. able changes in geometry, specifically in height. This The algorithm classifies points as road points (class 1) simplification means that the primary feature of a or nonroad points, and works as follows: road edge reduces to changes in the height of the ground surface. Second, each LIDAR scan is pro- 1. Collect coefficients for the current detail cessed independently, as opposed to building a 3D level, i. point cloud. This simplifies the algorithm to consider 2. Label each coefficient with the label of the input data along a single dimension. The curb detec- coefficient at detail level i − 1, which repre- tion algorithm consists of three main steps: prepro- sents the same portion of the signal. cessing, wavelet-based feature extraction, and post- 3. Calculate ŷroad using these labels. processing. 4. Relabel coefficients by absolute distance The preprocessing stage provides two important from ŷroad , where the distance threshold for features: mitigation of false positives due to occlu- detail level i is given as di . In other words, sions and sparse data, and formatting the data for fea- points are labeled by the function ture extraction. False geometric cues can result from striking both foreground and background objects or 1 if y[n] − ŷroad | ≥ di class, (y[n], i) = . (11) be due to missing data in a scan. Foreground ob- 0 otherwise jects are typically detected as obstacles (e.g., cones, telephone poles) and do not denote road edges. To 5. Continue to detail level i + 1. handle these problems, points are initially clustered by distance between consecutive points. After clus- Postprocessing applies a few extra heuristics to tering, small groups of points are removed from the eliminate false positives and detect some additional scan. A second pass labels the points as dense or nonroad points. Using the dense/sparse labeling sparse based on the distances between them. The from preprocessing, nonroad labels in sparse sections dense points are then linearly resampled in order to are moved from the sparse points to the neighbor- produce an input sequence of 2n heights. ing dense point closest to the vehicle. Because all The wavelet-based feature extraction step ana- LIDARs on the vehicle look downward, the closer lyzes height data through a discrete wavelet trans- point corresponds to the higher surface (e.g., berm, form using the Haar wavelet (Daubechies, 1992). The wall) creating the geometric cue. Afterward, sparse Haar wavelet is defined by the mother wavelet and points are removed from the classification list. The re- scaling function: sulting list represents the locations of the likely road and surrounding geometric cues. Figure 11 illustrates ⎧ ⎪ if 0 ≤ t < 12 , the performance of the algorithm in a typical on-road ⎨1 scene from the Urban Challenge. (t) = −1 if 12 < t < 1, (9) ⎪ ⎩ 0 otherwise, ⎧ 4.3. Roadmap Localization ⎨ 1 if 0 ≤ t < 1, ϕ(2j t − i) = j > 0 ∧ 0 ≤ i ≤ 2j − 1. Boss is capable of either estimating road geometry or ⎩ localizing itself relative to roads with known geome- 0 otherwise, try. Most urban roads change shape infrequently, and (10) most urban driving can be thought of as responding to local disturbances within the constraints of a fixed The Haar transform results in a sequence of coef- road network. Given that the shape and location of ficients representing the scaled average slopes of the paved roads change infrequently, our approach was Journal of Field Robotics DOI 10.1002/rob
438 • Journal of Field Robotics—2008 Figure 10. A single frame from the feature extraction algorithm. The top frame contains the original height signal (thick line). The window boundaries are from a single-detail level of the transform. The bottom frame shows the wavelet coeffi- cients for each window. to localize relative to paved roads and estimate the timation algorithms were heavily tested and proved shape of dirt roads, which change geometry more fre- to be effective. Despite confidence in the road shape quently. This approach has two main advantages: estimation system, it was not enabled during the Urban Challenge competition. Based on the way • it exploits a priori knowledge to eliminate the point density and aerial imagery of the UCFE course, necessity of estimating road shape in most the team determined that there was not a need to es- cases; timate road shape. A description of the road shape • it enables the road shape estimation problem estimation approach is provided in Section 4.4 for to emphasize geometric cues such as berms completeness because it enables Boss to drive on gen- and bushes, which are common in environ- eral roads and was ready to be used in the event, if ments with dirt roads and easier to detect at necessary. long range than lane markings. This approach led to two independent algo- 4.3.1. Localization Inputs rithms, one to provide a smooth pose relative to a The localization process can be thought of as trans- road network, and one to estimate the shape of dirt forming the pose provided by a global position- roads. The two algorithms are never operated si- ing system (GPS)–based pose estimation system multaneously, thus avoiding complex interactions be- into a smooth coordinate frame registered to a tween them. Both the localization and road shape es- road network. To do this it combines data from a Journal of Field Robotics DOI 10.1002/rob
Urmson et al.: Autonomous Driving in Urban Environments: Boss and the Urban Challenge • 439 (a) (b) (c) Figure 11. Overhead view of a road section from the Final Event course (a). Points show nonroad points (b). Overlay of nonroad points on imagery (c). Table II. Error characteristics of the Applanix POS-LV, as the nominal performance of this system with and reported by Applannix. without GPS. The POS-LV is configured to slightly outperform the nominal performance specifications Error with GPS Error after through the use of a combination of Omnistar Virtual and differential 1 km of travel Base Station and High Precision services. By incor- corrections without GPS porating the High Precision data, nominal perfor- Planar position, m 0.3 0.88 mance is improved to a 0.1-m planar expected posi- Heading, ◦ 0.05 0.07 tioning error. Whereas a positioning accuracy of 0.1 m sounds sufficient to blindly localize within a lane, these correction signals are frequently disrupted by even small amounts of overhead vegetation. Once commercially available position estimation system disrupted, this signal’s reacquisition takes approxi- and measurements of road lane markers with an an- mately a half hour. Thus, relying on these correc- notated road map. tions is not viable for urban driving. Furthermore, The initial global position estimate is received lane geometries may not be known to meter accu- from a device (POS-LV) developed by the Applanix racies a priori. It is critically important to be local- Corporation. This system fuses GPS and inertial and ized correctly relative to the lane boundaries, because wheel encoder data to provide a 100-Hz position esti- crossing over the lane center could have disastrous mate that is robust to GPS dropout. Table II describes consequences. Journal of Field Robotics DOI 10.1002/rob
440 • Journal of Field Robotics—2008 To detect lane boundaries, down-looking SICK These three error sources are grouped into two LMS lasers are used to detect the painted lane mark- classes; discontinuous errors (such as jumps) and ers on roads. Lane markers are generally brighter continuous errors (drift and model errors). With than the surrounding road material and are detected every new state measurement, the change in position by convolving the intensities across a line scan with x is checked for validity based on measured wheel a slope function. Peaks and troughs in the response speed v, anticipated percentage velocity error ζ , al- represent the edges of potential lane marker bound- lowed position jitter ε, travel direction θ , and allow- aries. To reduce false positives, only appropriately able travel direction error τ : spaced pairs of peaks and troughs are considered to be lane markers. Candidate markers are then further reject = |x| > v(1 + ζ )t + ε ∨ filtered based on their brightness relative to their sup- port region. The result is a set of potential lane marker x cos(θ ) (|x| > ε) ∧ · > τ . (12) positions. |x| sin(θ ) The road map used for localization encodes both correct local geometry and information about the In Eq. (12), the first term ensures that the reported presence or absence of lane markings. Although it motion of the vehicle is not significantly greater than is possible for road geometry to be incorrect glob- the anticipated motion given the vehicle wheel speed. ally, the local geometry is important to the estima- The second term ensures that for any significant mo- tion scheme, as will be described below. If the road tion, the reported motion is in approximately the geometry is not well known, the map must indicate same direction as the vehicle is pointed (which is ex- this. When the vehicle traverses parts of the map with pected for the speeds and conditions of the Urban poor geometry, the road shape estimation algorithms Challenge). If x is rejected, a predicted motion is operate and the road map localization algorithms are calculated based on heading and wheel speed. The disabled. residual between the prediction and the measured change in position is accumulated in a running sum, which is subtracted from position estimates reported by the POS-LV. In practice, values of ζ = 0.05, ε = 0.02, 4.3.2. Position Filtering and τ = cos(30 deg) produce good performance. To transform the measurements provided by the Correcting for the continuous class of errors is POS-LV to a smooth, road-network-registered frame, how localization to the road model is performed. The we consider three potential sources of position error: localization process accumulates lane marker points (LMP) generated by the laser lane marker detection algorithms. After a short travel distance, 1 m during 1. Position jumps. Despite the availability of in- the Urban Challenge, each LMP is associated with a ertial information, the POS-LV will occasion- lane boundary described in the road model. The dis- ally generate position jumps. tance of the corrected global position p for each LMP 2. Position drift. The correction signals, vari- from the lane center is calculated, and the projection ation in satellite constellation, and iono- point onto the lane center pc is noted. Half of the spheric disturbances cause slowly various lane width is subtracted from this distance, resulting changes to the position reported by the POS- in the magnitude of the local error estimate between LV. the lane boundary position and the model of the lane 3. Road model errors. Our approach to creating boundary position. This process is repeated for each road maps is to manually extract road shapes LMP, resulting in an error estimate: from aerial imagery. Modern aerial imagery can provide quarter-meter or better image i i i nLMP p − p i − w l · p − pc . i resolution, but global registration is gener- 1 eLMP = ally good only to a meter or worse. Distor- nLMP c 2 p i − p i 1 c tion in the imagery generally has a low spa- (13) tial frequency, so that the local shape of the This represents the error in the current filtered/ road is accurate, but the apparent global po- localized position estimate; thus the eLMP repre- sition may be inaccurate. sents how much error there is between the current Journal of Field Robotics DOI 10.1002/rob
Urmson et al.: Autonomous Driving in Urban Environments: Boss and the Urban Challenge • 441 combination of the existing error estimate and posi- 4.4.2. State Vector tion. In practice, we further gate the error estimates, To represent the parameters of a road, the following discarding any larger than some predetermined max- model is used: imum error threshold (3 m during the Urban Chal- lenge). Over time, error estimates are accumulated s(t) = [x(t), y(t), ϕ(t), C0 (t), C1 (t), W (t)], (15) through a recursive filter: ecur = eprev + αeLMP . (14) where [x(t), y(t), φ(t)] represents the origin and orien- tation of the base of the curve, C0 (t) is the curvature This approach generates a smooth, road-network- of the road, C1 (t) is the rate of curvature, and W (t) referenced position estimate, even in situations in is the road width. A Taylor series representation of a which GPS quality is insufficient to otherwise local- clothoid is used to generate the actual curve. This is ize within a lane. This solution proved to be effective. represented as During prechallenge testing, we performed several tests with GPS signals denied (through the placement t t y(x) = tan[ϕ(t)]x + C0 x 2 + C1 x 3 . (16) of aluminum caps over the GPS antennas). In one rep- 2 6 resentative test, the vehicle was able to maintain po- sition within a lane, while traveling more than 5.7 km without GPS. During this test, the difference error in 4.4.3. Particle Filter the POS-LV position reached up to 2.5 m, more than The road estimator uses an SIR (sample importance enough to put the vehicle either off the road or in an- resample) (Duda & Hart, 1972) filter populated by other lane if not compensated for. 500 particles. Each particle is an instantiation of the state vector. During the sampling phase, each parti- cle is propagated forward according to the following 4.4. Road Shape Estimation set of equations, where ds represents the relative dis- To robustly drive on roads where the geometry is not tance that the robot traveled from one iteration of the known a priori, the road shape estimator measures algorithm to the next: the curvature, position, and heading of roads near the vehicle. The estimator fuses inputs from a variety of (ds)2 (ds)3 LIDAR sensors and cameras to composite a model of y = y + ϕds + C0 + C1 , (17) the road. The estimator is initialized using available 2 6 prior road shape data and generates a best-guess road (ds)2 ϕ = ϕ + C0 ds + C1 − dϕ, (18) location between designated sparse points where a 2 road may twist and turn. The road shape is repre- C0 = C0 + C1 ds, (19) sented as the Taylor expansion of a clothoid with an offset normal to the direction of travel of the vehicle. C1 = (0.99)C1 . (20) This approximation is generated at 10 Hz. The final C1 term represents the assumption that the curvature of a road will always tend to head toward 4.4.1. Sensor Inputs zero, which helps to straighten out the particle over Two primary features were used to determine road time. After the deterministic update, the particle fil- location. ter adds random Gaussian noise to each of the di- Curbs represent the edge of the road and are de- mensions of the particle in an effort to help explore tected using the Haar wavelet (see Static Obstacle sudden changes in the upcoming road curvature that Detection and Mapping section). When curbs are de- are not modeled by the curve parameters. In addition tected, the estimator attempts to align the edge of the to Gaussian noise, several more directed searches are parametric model with the detections. performed, in which the width of the road can ran- Obstacles represent areas where the road is un- domly increase or decrease itself by a fixed amount. likely to exist and are detected using the obstacle de- Empirically, this represents the case in which a road tection system. The estimator is less likely to pick a suddenly becomes wider because a turn lane or a road location where obstacle density is high. shoulder has suddenly appeared. Journal of Field Robotics DOI 10.1002/rob
You can also read