evs30 symposium - arxiv · evs30 symposium stuttgart, germany, october 9 ... method as presented in...

12
EVS30 Symposium Stuttgart, Germany, October 9 - 11, 2017 Autonomous Electric Race Car Design Niklas Funk 1 , Nikhilesh Alatur 1 , Robin Deuber 1 , Frederick Gonon 1 , Nico Messikommer 1 Julian Nubert 1 , Moritz Patriarca 1 , Simon Schaefer 1 , Dominic Scotoni 1 , Nicholas B ¨ unger 1 Renaud Dub´ e 1 , Raghav Khanna 1 , Mark Pfeiffer 1 , Erik Wilhelm 2 , Roland Siegwart 1 1 ETH-Zurich, R¨ amistrasse 101, 8092 Zurich 2 Kyburz Switzerland AG, Shedweg 2-8, 8427 Freienstein-Teufen Abstract Autonomous driving and electric vehicles are nowadays very active research and development areas. In this paper we present the conversion of a standard Kyburz eRod into an autonomous vehicle that can be operated in challenging environments such as Swiss mountain passes. The overall hardware and software architectures are described in detail with a special emphasis on the sensor requirements for autonomous vehicles operating in partially structured environments. Furthermore, the design process itself and the finalized system architecture are presented. The work shows state of the art results in localization and controls for self-driving high-performance electric vehicles. Test results of the overall system are presented, which show the importance of generalizable state estimation algorithms to handle a plethora of conditions. Keywords: autonomous, navigation, BEV (battery electric vehicle), teach and repeat 1 Introduction Due to the vast advances in computing and sensing systems, work in autonomous driving has grown significantly within the last decade. While the idea of autonomous vehicles has been around for many years the DARPA grand challenge [1] was one of the first major forays into self-driving vehicles. The task of autonomous driving can be split into two main parts: (i) The perception, localization and state estimation and (ii) the motion planning and control task. Regarding localization it is important that the vehicle can precisely estimate its current state w.r.t. the environment. The motion planning and control part assures that the vehicle behaves as expected and executes the planned actions reliably. In this work we present an autonomous driv- ing application based on a visual teach-and-repeat method as presented in [2]. During a demonstra- tion (teaching) run, a human vehicle operator pro- vides a demonstration of how he wants the vehicle to drive in a given environment. During that run, a visual feature map of the environment is built using a Simultaneous Localization and Mapping (SLAM) method and the vehicles’ position in this map is recorded. An alternative to the visual SLAM would be laser-based approaches as shown in [3] or [4]. However, since camera-based systems have a significantly lower cost than laser-based ones, in this work we will focus on the approach [5] based on visual and inertial measurements. In the repeat phase, the car localizes in the pre-recorded feature map and follows the teach path as close as possible using a reference tracking controller. Although we can assume that the taught path is col- lision free we still have to ensure that the car op- erates safely at any time. Therefore, in addition to the stereo camera used for localization we use a laser-based obstacle detection system that allows to safely detect objects which are blocking the vehi- cles reference path. The approach presented in this work only requires local sensing and has no need for continuous lane markings or a GNSS signal. The main contributions of this work are: The conversion of a stock electric vehicle into an autonomous driving platform A visual teach-and-repeat pipeline based on state-of-the art localization and control tech- niques EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 1 arXiv:1711.00548v1 [cs.RO] 1 Nov 2017

Upload: dangnhi

Post on 19-Aug-2018

213 views

Category:

Documents


0 download

TRANSCRIPT

EVS30 SymposiumStuttgart, Germany, October 9 - 11, 2017

Autonomous Electric Race Car Design

Niklas Funk1, Nikhilesh Alatur1, Robin Deuber1, Frederick Gonon1, Nico Messikommer1

Julian Nubert1, Moritz Patriarca1, Simon Schaefer1, Dominic Scotoni1, Nicholas Bunger1

Renaud Dube1, Raghav Khanna1, Mark Pfeiffer1, Erik Wilhelm2, Roland Siegwart11ETH-Zurich, Ramistrasse 101, 8092 Zurich

2Kyburz Switzerland AG, Shedweg 2-8, 8427 Freienstein-Teufen

Abstract

Autonomous driving and electric vehicles are nowadays very active research and development areas. Inthis paper we present the conversion of a standard Kyburz eRod into an autonomous vehicle that canbe operated in challenging environments such as Swiss mountain passes. The overall hardware andsoftware architectures are described in detail with a special emphasis on the sensor requirements forautonomous vehicles operating in partially structured environments. Furthermore, the design processitself and the finalized system architecture are presented. The work shows state of the art results inlocalization and controls for self-driving high-performance electric vehicles. Test results of the overallsystem are presented, which show the importance of generalizable state estimation algorithms to handlea plethora of conditions.

Keywords: autonomous, navigation, BEV (battery electric vehicle), teach and repeat

1 IntroductionDue to the vast advances in computing and sensingsystems, work in autonomous driving has grownsignificantly within the last decade. While the ideaof autonomous vehicles has been around for manyyears the DARPA grand challenge [1] was one ofthe first major forays into self-driving vehicles.The task of autonomous driving can be split intotwo main parts: (i) The perception, localization andstate estimation and (ii) the motion planning andcontrol task. Regarding localization it is importantthat the vehicle can precisely estimate its currentstate w.r.t. the environment. The motion planningand control part assures that the vehicle behaves asexpected and executes the planned actions reliably.In this work we present an autonomous driv-ing application based on a visual teach-and-repeatmethod as presented in [2]. During a demonstra-tion (teaching) run, a human vehicle operator pro-vides a demonstration of how he wants the vehicleto drive in a given environment. During that run,a visual feature map of the environment is builtusing a Simultaneous Localization and Mapping(SLAM) method and the vehicles’ position in this

map is recorded. An alternative to the visual SLAMwould be laser-based approaches as shown in [3]or [4]. However, since camera-based systems havea significantly lower cost than laser-based ones, inthis work we will focus on the approach [5] basedon visual and inertial measurements. In the repeatphase, the car localizes in the pre-recorded featuremap and follows the teach path as close as possibleusing a reference tracking controller.Although we can assume that the taught path is col-lision free we still have to ensure that the car op-erates safely at any time. Therefore, in additionto the stereo camera used for localization we use alaser-based obstacle detection system that allows tosafely detect objects which are blocking the vehi-cles reference path. The approach presented in thiswork only requires local sensing and has no needfor continuous lane markings or a GNSS signal.The main contributions of this work are:

• The conversion of a stock electric vehicleinto an autonomous driving platform

• A visual teach-and-repeat pipeline based onstate-of-the art localization and control tech-niques

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 1

arX

iv:1

711.

0054

8v1

[cs

.RO

] 1

Nov

201

7

• Real-world tests with the autonomous plat-form in the challenging environment of aSwiss mountain pass.

The paper is structured as follows: In Section 2 wegive an overview of our platform. In Section 3 wepresent the architecture of the system and presentthe submodules. Section 4 provides informationabout our safety measures, Section 5 presents theresults before we conclude in Section 6.

2 ARC Overview

Figure 1: An illustration of our Autonomous eRod. Thesensors, actuators and computer providing autonomousdriving functionalities are shown in red.

The modified Kyburz eRod with a series of addi-tional sensors is shown in Figure 1. The eRod isan all-electric vehicle produced by Kyburz Switzer-land and sold in European Markets and was pro-vided to the ETH-Zurich final year student team formodification into a self-driving vehicle. The eRodhas a nominal power of 15kW, and a peak power of45kW, which, combined with its low weight of only500kg, makes it a very nimble vehicle designed forfun and racing applications.In order to control the vehicle via digital com-mands, new actuators had to be deployed. Namely,a new steering unit provided by TKP which can becontrolled via CAN was incorporated. Secondly,a new braking system was designed, consisting ofan electric motor which pulls the braking pedal viametal cables and which can be controlled usingan analog voltage input, and another voltage inputwhich physically simulates the existing throttle po-tentiometer.The choice of sensors is shown in Figure 1. Our lo-calization algorithms rely on the input from the Vi-sual Inertial sensor (VI sensor) which is mountedon the bonnet. This sensor module contains twocameras together with an intertial measurementunit (IMU). The sensor is mounted in a way toallow adjustment of the sensor’s angle around thepitch axis which is crucial since the view of thecameras has to be well-chosen. On the one handit should not capture the sky since it is alteringvery quickly and therefore does not provide goodfeatures for re-localization. On the other hand,it should neither see the bonnet nor the vehicle’sshadow which would confuse the vision based

odometry estimate. An inclination angle of 11 de-grees was found to optimally satisfy both of thesecriteria.The detection of obstacles relies on a VelodyneVLP-16 LiDAR sensor which is mounted on top ofthe roll bar. We selected a LiDAR sensor against aradar sensor as the latter can pose difficulties whendetecting special surfaces and has a limited angu-lar resolution[6]. The VLP-16 was therefore cho-sen in order to allow an optimal obstacle detectionand for enabling the investigation of future researchavenues such as dynamic obstacle avoidance andLiDAR-based localization[7].The on-board sensor system also has two rotarywheel encoders which are read out using a FPGAon a National Instruments compact RIO VehicleControl Unit and a Steering Angle encoder which isread out using a dSpace Micro AutoBox II. The useof two seperate VCUs is not desirable from a com-plexity perspective, but saved lots of time due to theTKP steering unit having manufacturer-suppliedSimuLink blocks and team familiarity with Lab-View.All the sensor information is fused on our Linux-based computer running ROS which completes thesystem showed in 2.

Figure 2: General system overview

The computer is the core of the autonomous sys-tem, taking care of the state estimation, obstacle de-tection, and finally the computation of the controlcommands which are then in return passed throughour Interface to the two VCUs, where the low-levelPID-controllers for velocity and steering angle areimplemented. They compute the necessary analogvoltages for our throttle and braking system andCAN messages for the TKP steering unit. The ve-locity controller and the steering angle controllerhave an average tracking error of 0.0614 m/s and0.1894 degrees, respectively. (see Figure 3)The information passing between the computer andthe two VCUs is established through an interfacewhich we designed (see Figure 4), running at 200Hz and using the User Datagram Protocol (UDP).The interface was kept as easy as possible to en-sure transparency and low latency. Since in thisparticular architecture the compact RIO is capa-ble of controlling the car’s velocity, it is the mainVCU and takes control of the steering, permanentlychecks all UDP connections and inherits all thesafety measures on the VCU level.

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 2

Figure 3: Low-level controller performance. Top: ve-locity controller. Bottom: steering controller.

Figure 4: Control System layout

3 System ArchitectureIn order to make a vehicle drive autonomously, var-ious different modules are required. Figure 5 pro-vides and overview of sensors and modules used inour pipeline.

Figure 5: Software Systems layout

3.1 Teach-and-RepeatOur work is based on the teach-and-repeat method.Similar to how localization is performed on a streetmap, our car localizes using a previously recordedmap of visual features. The mapping (teach phase)is essential since there is no global feature mapwhich we could use. In the second step (repeatphase) the car is able to drive the same (or an opti-mized) path autonomously (repeating). While op-timizing the path would be a further development,we follow the same path of the teaching part.

3.2 State EstimationIn our system, there are three inputs for estimat-ing the odometry / state of the vehicle: An estimatethrough vision (optical flow), the IMU, and the ve-hicle model. For the state estimation, the three dif-ferent kinds of inputs need to be fused.Using the current velocities of the rear wheels aswell as the current steering angle in combinationwith a kinematic vehicle model (see Figure 6) onecan compute a local estimate of the current velocityin a single plane. Since the car will not be operatedat its limits of handling (due to limitations imposedby the state estimation) we decided to use a kine-matic bicycle model and make a no slip assump-tion. An important point is that the velocities haveto be expressed in the right coordinate frame whichis in our case at the position of the VI-sensor, rightbetween the front wheels.

3.3 ROVIOIn the three dimensional surrounding of a moun-tain pass it is not sufficient to assume that the planewill be maintained from the start until the end ofthe drive, therefore we need additional software

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 3

Figure 6: Vehicle Model

to compute the three dimensional car odometry.ROVIO is a visual odometry program developed byMichael Bloesch [8]. It combines a vision-basedodometry estimation with an extended Kalman fil-ter to weight and merge the car model, the vision-based estimate and the IMU measurements.Before adding the vehicle model to ROVIO, theodometry estimate was not reliable. The reason forthis lay in error-prone IMU measurements in ourspecial application, lacking strong and frequent ac-celerations compared to a flying UAV but adaptingthe covariances of the vehicle model and the esti-mates by the IMU solved the issue.Unfortunately ROVIO only uses one CPU core andis therefore limited in computing power. Whentracking too many features in a difficult environ-ment (i.e. the majority of features too far away ora grave change in tracked features between consec-utive images) the computational load is too largeand processing one image takes longer than fetch-ing a new one, resulting in an increasing lag. Lagwould lead to a delay in control which can yield ve-hicle instabilities and therefore has to be avoided.The first approach, reducing the queue size of theincoming image stream, did not help since ROVIOrequires a pixel flow. However decreasing the max-imum number of features being tracked and thepatch size from six to four helped without sacri-ficing too much accuracy.Furthermore, another measure to use the limitedcomputing power more efficiently is to discard badfeatures more quickly and not to waste too muchcomputing power on them. This was achieved byreducing the detection threshold for new featuresand by increasing the removal factor, if there arenot enough free features. There exists a trade-offbetween a low detection threshold and the maxi-mum number of features. A low maximum numberof features needs a higher detection threshold. Ifnot, the set of features changes too fast resulting ina bad estimate. We achieved the best results using amaximum of 20 features and a detection thresholdof 0.3.The most important parameter was the PenaltyDis-tance. Simply put, this parameter determines howhomogeneously distributed and close the trackedfeatures can be to each other. Since the close fea-tures show a greater change in position betweenconsecutive frames, resulting in an easier veloc-ity estimate, and since sometimes half of the pic-ture can be made up of blue sky without any gra-dient, we allowed the features to be closer to eachother. Nevertheless, a too small PenaltyDistancedoes not help either because this can lead to a few

places where all features are clustered, which in-creases the probability of losing them altogetherwhen the next image arrives. This change had ahuge impact and helped to eradicate lag completelythroughout the whole climb in conditions like wefaced on the Klausenpass. In the future, a furthertuning goal could be pushing the limit in terms ofvelocity, since our finally tuned version had prob-lems when driving through critical environments,where subsequent image frames differ drastically,at velocities greater than 30km/h. A representationof the optimized image for optical flow is shown in7.

Figure 7: Rovio is a visual odometry system, perform-ing optical flow to estimate vehicle geometry indepen-dent of environment. Top: Rovio before optimizationBottom: Rovio after optimization

3.4 ORB SLAM2The advantage of a mapping algorithm over asolely visual odometry-based pose estimation canbe found in the reduced drift. In terms of local-ization and mapping we decided to use a vision-based approach (ORB-SLAM2 [9]) instead of aLiDAR-based one (SegMatch) or a fusion of both(Google Cartographer [10]). Googles cartographerwas not chosen since it is designed to be used inindoor environments at very low speeds. The rea-son for preferring ORB-SLAM2 rather than Seg-Match lies within our target surroundings and con-ditions. While with visual teach and repeat, as-suming enough light, one can get hundreds of fea-tures in every image, a LiDAR-based approachonly works when enclosed, geometrical shapes canbe detected and extracted which is not the case ona mountain road.

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 4

ORB-SLAM2, developed by Raul Mur-Artal [9],uses the raw stereo camera data of the VI as in-put allowing the calcualtion of each features’ posevia triangulation. During teach, ORB-SLAM2 de-tects features according to the ORB-classificationand stores the best suitable features in a global map.An example of such a built map can be seen in Fig-ure 8. During the repeat part, ORB-SLAM2 com-pares the currently seen features with those storedin the map.If there are enough matching features, apose estimation of the car can be calculated.

Figure 8: Orbslam operational principle. Green featuresare known from the teach part. Blue are features that areunknown.

Ueli Graf fused ROVIO and ORB-SLAM2 ([11])which reduces the needed computation power,since ROVIO’s odometry estimate is more accu-rate compared to ORB SLAM’s standard internalodometry estimate. Furthermore, in order to reducesmall jumps produced by the internal ORB SLAM2pose optimizer, we added a pose estimate basedon the robust and locally accurate odometry input.This also allows a dead reckoning mode which con-tributes to robustness in the repeating part. Thedead reckoning mode occurs when ORB-SLAM2does not find enough matching features to localize.Then, the pose is calculated by only integrating theodometry until ORB-SLAM2 can localize again inthe recorded map.Moreover, an algorithm for concatenating severalmaps, where each map is at a maximum lengthof 3.3 km, was implemented in order to test longruns without the necessity to load a large map whenrestarting the system (2min per km up to a lengthof 3km). This ensures to test more efficiently, re-duces the usage of RAM and consequently makesthe whole setup more robust. When arriving at theend of a small sub-map, the car stops, the algo-rithm closes and restarts ORB-SLAM2, loads thesuccessive map, waits until the new map is loadedand then the car itself will continue the autonomousrun.In order to control the steering angle and the ve-locity of the car in the repeating phase, a referencepath from the teaching part is necessary. The ref-erence path is created by storing the vehicle poseestimates during the teach phase. While driving inthe repeat phase, the current pose together with theclosest point on the reference path and the odom-etry estimate are sent to the path following con-troller.The position estimation of the improved and op-timized ORB-SLAM2 can be seen in Figure 9.The dark red reference path is created with GNSSdata. The blue path from ORB-SLAM2 has someglobal drift compared to the GNSS data. Never-

theless, considering local accuracy, ORB-SLAM2performed more robust and better than the GNSSpose. In conclusion, our fully optimized ORB-SLAM2 version provides a stable and robust map-ping algorithm, which is capable of performing inseveral different surroundings: Urban areas, ruralareas and on mountain roads.

Figure 9: Orslam performance

3.5 Trajectory FollowingIn order to follow the recorded path during therepeating phase, appropriate target velocities andsteering angles have to be computed which willthen be put in practice by the VCUs and actu-ators. The implemented solutions were stronglyinfluenced by our project’s specific needs; track-ing a recorded path on a curvy and narrow moun-tain road. Control theory provides innumerableapproaches for trajectory tracking, starting froma PID controller over to a simpler geometricalcontroller, in case of Single Input Single Output(SISO) analysis, up to optimal control approachessuch as MPC and LQR for considering a MultipleInput Multiple Output (MIMO) system. With theintention to keep the controllers clearly structured,steering angle and velocity control were decoupledand can hence be resolved separately using SISOapproaches.

Steering Angle ControlThe task of the steering angle controller is to com-pute a target angle from the reference path andthe current pose of the car. Since path planningcould not be implemented due to missing informa-tion about the lane boundaries, the only goal wasto track the teaching path as accurately as possible.Inspired by [12], we chose to implement the PurePursuit Controller: A controller based on a geo-metric bicycle model. According to [13], at lowerspeeds, the kinematic bicycle model approximationusing simple geometrical relations is at least as ac-curate as a dynamic model, which estimates thedynamics of the car using the attacking forces andtorques. Hence, the moderate velocities in our tar-get environment justified the use of the geometric

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 5

bicycle model. Figure 10 illustrates the base con-cept of the Pure Pursuit steering controller.The advantages of the chosen path tracking algo-rithm are its explicit geometrical concept and itsindependence from velocity control. The controllerconsists of one explicit equation, allowing the useof non-linearized models like the bicycle model.This spares us the effort of linearization in everysingle iteration.

δ = 0.8 · tan−1(2Lsin(α)

ld) (1)

Figure 10: Pure pursuit controller.

Where:

• δ: The required steering angle for trackingthe path

• L: The car’s wheelbase

• α: The angle between the reference pointand the local x-axis of the vehicle

• ld: The distance of the reference point on thereference path from the vehicle

The shown formula computes a steering angle,given a reference point on the reference path wewant to reach. The factor 0.8 was added to the con-ventional formula due to better performance duringtest optimization. In our implementation the look-ahead distance ld determines the reference pointby specifying its distance from the current positionand is described by a function, which is propor-tional to the current velocity with a static (k2lad s)and a dynamic tuning knob (k1lad s).

ld = k2lad s + k1lad s · vabs (2)As Figure 11 shows, we decided to use the look-ahead distance (ld) not as an absolute distance butas an Euclidean distance summed up along pathpoints, starting from the point on the path whichis currently the closest to the car in order to preventthe car from cutting the curves.On the one hand, the look-ahead distance ld needsa lower bound, 3.5 meters, in order to prevent thecar from choosing too close a reference point at lowspeeds, which causes the car to oscillate around thereference path. On the other hand, an upper boundof 13 meters improves the tracking quality by pre-venting the cutting of curves. Once an adequate

Figure 11: Distance of reference points

reference point is chosen, it is transformed to thelocal coordinate frame of the car and then the re-quired steering angle is found by using the PurePursuit Controller formula.

Velocity ControlThe eRods velocity is the second control variable.To get an easily tunable reference velocity, a con-nection to the velocity of the teaching part is kept,while independently calculating a feasible velocitywith respect to the upcoming path section. To de-termine a physically meaningful reference velocitywe apply Coulomb’s friction law between tyre andasphalt:

vref physical =√µfric · gearth · curveradius (3)

Where:

• µfric: The static friction coefficient betweenthe tyres and the asphalt

• gearth: The earth’s gravitational pull

• curveradius: An approximated curve radius

This curve radius is found by fitting circles in theregion of interest. The region of interest is deter-mined by a specific distance which is calculatedsimilarly to ld in the Pure Pursuit Steering Con-troller:

ld = k2lad v + k1lad v · vabs (4)k1lad v and k2lad v represent an empirically deter-mined dynamic gain and a static offset. Since thephysical limit reaches infinity on an approximatelystraight path, the velocity is constrained to be lowerthan two upper boundaries. One is related to thevelocity at the current position during the teachingpart (vteach + vfreedom), where vfreedom is a user-chosen parameter. The other is a maximum veloc-ity based on the given environment (maxabs vel)and also defined by the user. After this first step,the reference velocity is:

vref = min(vref physical; vteach+vfreedom;maxabs vel)(5)

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 6

During testing, we noticed that the velocity is al-most always bounded by the teaching or user-chosen velocity limit and not by Coulomb’s fric-tion law. In the next step, the previous referencevelocity vref is further adapted by applying differ-ent penalizations which in some cases might evenshrink vref to zero. This is done by multiplyingvref with four different factors. The four factorsare the penalization factor for a certain obstacle dis-tance, lateral error, distance to the end of our pathand time from GUI Shut-down. Each of the func-tions, shown in Figure 12, determine the penaliza-tion factor and can be easily adapted.

Figure 12: Our four different penalization factors.

4 Safety SystemsWhen developing an autonomous vehicle, the mostimportant goal is to guarantee a maximum amountof safety at any point in time. Therefore we setup four safety layers (see Figure 13) and decidedto always have a person in the driver seat who cantake over the eRod at any time.

Figure 13: Cascading security levels

Obstacle DetectionThe ability to react to obstacles blocking the up-coming reference path is crucial for the safety of

our car and its surrounding, and in theory elimi-nates the need for a person sitting in the driver seat.The most important characteristic of a reliable ob-stacle analysis on a curvy mountain road is that theimplemented solution takes the future trajectory ofthe car into account. This allows the car to drivethrough tight curves without classifying the road-sides as obstacles and works as follows: In the firststep, all potential obstacles in the car’s proximitymust be detected. In the second step, the grid mapis analyzed whether any of the obstacles block theupcoming path section.

3D Object Detection The obstacle detection al-gorithm relies on the point clouds received from theLiDAR. At first, all points received from the Li-DAR are assigned to certain vertical angles (e.g. α,β) as shown in Figure 14.

Figure 14: Visualisation of vertical angles (meaning α,β).

The algorithm is based on the fact that the pointsbelonging to one vertical angle form a circle aroundthe car (see Figure 15) resulting in a constant dis-tance. In case of an ascending road, the points onthe road form an ellipse. However, the change ofthe distance between consecutive points on the el-lipse and the laser is small compared to the gravechange in distance if an obstacle is present, whichresults in a simple detection of obstacles.

Figure 15: Schematic of the obstacle detection.

For each vertical angle, all points outside a triangleof 90 degrees, which turns in line with the currentsteering angle, in front of the car are filtered outto analyze the region of the street only. Throughstatistical analysis of the remaining points, a dis-tance interval can be determined which containsmost of the points and therefore, assuming no ob-stacles blocking the majority of the road, returnsthe distance between the LiDAR and the road. Inthe next step, the x- and z- coordinates of adjacentpoints are compared as follows: If one of the ad-jacent point was detected as a point on the roadand the summation of the difference in x- and z-direction lays in a certain empirically determinedtolerance, both points are labeled as road. If how-ever, the difference in distance is larger than thetolerance, the other point is marked as belonging toan obstacle. The y- coordinate is ignored becausenot each laser beam gets reflected resulting in an

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 7

incorrect distance in y-direction. Furthermore, ifthere are any points at a vertical angle of 0 degree,they are automatically labeled as obstacles, mak-ing it possible to detect a flat wall in front of thecar. In the final step, all points labeled as obstaclesare projected into the horizontal plane and markedin an occupancy grid map. This grid map is thensent to the grid map analyzer.However, our current 3D-object detection algo-rithm has a decreased ability to detect a flat objectblocking the whole road. The positioning of the Li-DAR in the front of the car just above ground mightresult in a simpler, more straight-forward and moreprecise obstacle detection but we wanted to keepthe possibility to implement a 360 degree obstacledetection.

Grid map Analyzer Due to the fact that our sys-tem does not include lane tracking, we developedan obstacle detection which stops in front of the ob-stacle and is not capable of driving around it whichis anyways very difficult on narrow roads like theKlausenpass. Because of our modular system, thiswould still be a possible further development.Not all objects displayed in the grid map representa potential danger for the car. That is why a gridanalysis is required which returns the distance tothe closest path blocking obstacle. The basis there-fore is the estimate of a ’dangerous zone’ whichat first has the form of the estimated future path.The thickness of this zone is the broadness of thecar plus a certain tolerance which is proportion-ally dependent on the tracking error (i.e. the lat-eral deviation from the planned path). After havingcomputed the ’dangerous zone’ it is added to thegrid map. Figure 16 visualizes the final grid mapincluding the ’dangerous zone’ (grey) and the de-tected obstacles (black). The comparison betweenthe ’dangerous zone’ and obstacles reveals if thereare any obstacles on the car’s future trajectory andif yes, the shortest obstacle distance is returned.

Figure 16: Rviz visualisation of the final grid map.

Depending on the measured distance, a distinc-tion between a critical and non-critical situation isperformed algorithmically, while the critical dis-tance interval is a function of the actual velocity:[0; (

vabs·3.610 )2].

Critical obstacles trigger an emergency brake whilenon-critical ones are passed to the controller whichdecreases the reference velocity through the corre-sponding penalization factor. If an obstacle causesthe car to stop but the car’s future trajectory is freedagain, the car automatically continues the run andreturns to the reference trajectory tracking task.If an obstacle is so small that it lies between twoLiDAR beams, the obstacle cannot be detected on

a frame-by-frame basis. This results in objects ap-pearing and disappearing from the grid map caus-ing the obstacle distance and therefore the refer-ence velocity to vary significantly in short time pe-riods. To prevent this, we added a time delay when-ever a recognized obstacle disappears. During thistime, the grid map analyzer simply assumes that theobject is still present. To manage the case in whichthe car comes to a stop exactly at a distance wherethe obstacle cannot be detected, another time inter-val of three seconds was introduced. During thisinterval, our car slowly moves forward to check ifthe obstacle is still present. This delay guarantees asmooth halt in front of small objects that are presentbut cannot be detected constantly.The obstacle distance is sent to our guard algo-rithm, which is checking this value amongst manyothers and eventually takes action by sending theemergency brake signal to the cRio and by decreas-ing the reference velocity to 0 m/s while the steer-ing controller keeps running. The reason for thisis that most of the times when an emergency brakewill be actuated, it is safer to continue controllingthe steering and not to steer randomly or to drivestraight. Other safety critical values are for instancethe car’s orientation, the tracking error, the outputof the System’s Watchdog and the VCUs’ status.

Further Safety MeasuresThe VCUs are the most essential pieces of hard-ware in order to guarantee a safe and robust systembecause of their direct connection to the actuators.Due to our special architecture, all safety measuresare performed by the cRIO because of its capabilityof controlling the cars’ velocity and of changing thevisual LED output. In case of any internal failure,e.g. an emergency stop sent by the computer, inter-face breakdown, human steering intervention or theend of an autonomous drive, the velocity controlleris disabled and the cRIO immediately switches theLEDs from blue to green. The first three previouslymentioned events also trigger the emergency brak-ing procedure which causes a full stop of the vehi-cle.The human steering intervention event is detectedwhenever the steering torque sensor measures atotal torque of more than 7.5 Nm acting on thesteering wheel. This threshold ensures that distur-bances, e.g. resulting from uneven roads, do notlead to a shut down.It is important to establish safety measures on thesoftware level, but the best way to guarantee safetyis their implementation on the physical hardwarelevel.A complete failure of the eRod 12V system willnot stop our autonomous system from running be-cause we installed additional batteries which canprovide all the electrical power needed by our sys-tem for about 15 minutes. An emergency buttonnext to the driver seat was installed which physi-cally cuts all actuators from power, and definitelystops the autonomous system from running. All ofthe connecting and disconnecting processes (whichalso change the color of the LEDs) are executed byindustrial relays which guarantee fail safeness formillions of switching events.

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 8

Moreover, the implementation of the braking sys-tem allows the driver to brake in every situationand physically override any command from the au-tonomous vehicle controller and thereby reduce thevelocity of the autonomous system. Like this, thedriver cannot only over-steer but also over-brakethe autonomous system at any time.We are very proud of having established such a ro-bust, quick and safe overall system together withits hardware implementation. This is one of themain reasons why we never had any accident withour vehicle throughout our 1000 km of testing. Itturned out that for the driver, the steering interven-tion is the best way to stop the system in case ofany failure or danger. Furthermore, if the computerwants the cRIO to trigger an emergency brake, thistakes less than 20 ms.

5 ResultsThe overall system demonstrates a good teachingand path following performance without being tooaggressive (see Figure 17). At velocities up to25 km/h, our system’s median path tracking erroris about 10 cm. As it can be seen in Figure 18,the curve cutting behavior emerges with increasingvelocities because of the high-level steering con-troller.

Figure 17: Performance at 20-25 km/h

Figure 18: Performance at 25-30 km/h

Our system was mainly optimized for usage on theKlausenpass, where most of the features are faraway from our vehicle. Our system works up toabout 35 km/h, but is nevertheless limited to a pathlength of 3.5 km using a single map only. Due tothe limiting testing time, we did not yet have thechance to test longer runs by concatenating severalsub-maps (of 3.3 km each). The inclination angleof our stereo camera allows a lateral tracking errorof (+/-2m) without losing localization fix. The ori-entation divergences must not be greater than (+/-

20 degrees). Our system stays in dead reckoningmode after 2 seconds of missing re-localization.Missing localization for longer than this period re-sults in a termination of the autonomous run. Dueto our vision-based approach, we are strongly de-pendent on the light conditions. In most cases wewere able to localize in a map for about 2.5 hoursbefore having to do a new teaching / mapping run.Bright light with a low angle of incidence as wellas routes taught on overcast days and repeated onsunny days (or the other way around) are particu-larly problematic.All in all, our system behaves similarly as Furgale’sMars rover ([2]) in many ways, e.g. light depen-dence. Nevertheless, because of our huge effort intesting and optimization the state estimation of oursystem seems to be very robust in terms of the re-peat deviation and our system works under highervelocities.

Figure 19: Logging file displayed during eachteach/repeat phase

6 ConclusionIn this paper we outline the results of modifyinga Kyburz eRod into a fully autonomous platform.An exhaustive description of the hardware and sys-tems was provided, as well as detailed test resultsthat show our state estimation and path followingcontrol under tough real-world conditions.Our vision was to conquer the Klausenpass with avision-based teach-and-repeat method only. We areproud that we realized our vision to autonomouslydrive up this difficult and unforgiving mountainroad for more than three kilometers. Using vision-based navigation in such a demanding environmentapplying the teach and repeat method is an ef-fective showcase for the potential of this technol-ogy. With further refinements to deal with chang-ing light conditions and remote features, this tech-nology promises great opportunities for the futureof autonomous driving and may also be extendedto other applications such as indoor navigation.The fact that ten bachelor students built an au-tonomous vehicle within nine months using a smallbudget compared to other companies also demon-strates the feasibility of autonomous driving. Withour system, we emphasized the safety of autonomy

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 9

and increased the enthusiasm of the public for thisexciting topic.For future efforts, merging several maps of thesame location recorded under different lightingconditions could even reduce the main disadvan-tage of visual localization, i.e. its dependence onlighting conditions. As a further improvement, wecould create a global map with all the streets wehave ever driven. If this global map would includethe desired route, the teaching phase would be ob-solete. In the near future, maybe the most feasibleapplication would be to implement this technologyfor the daily travel of the same route, e.g. the wayto the workplace of a commuter could be driven au-tonomously.

AcknowledgmentsThe authors would like to thank Hiag Data,Kyburz-Switzerland AG, ETH Zurich and the Au-tonomous Systems Lab (ASL), Thyssenkrup prestaAG, National Instruments, u-blox, Helbling andHasler for their financial, technical, and moral sup-port, without which this project would not havebeen possible.

References[1] S. Thrun, M. Montemerlo, H. Dahlkamp,

D. Stavens, A. Aron, J. Diebel, P. Fong,J. Gale, M. Halpenny, G. Hoffmann et al.,“Stanley: The robot that won the darpa grandchallenge,” Journal of field Robotics, vol. 23,no. 9, pp. 661–692, 2006.

[2] P. Furgale and T. D. Barfoot, “Visual teachand repeat for long-range rover autonomy,”Journal of Field Robotics, vol. 27, no. 5, pp.534–560, 2010.

[3] P. Krusi, P. Furgale, M. Bosse, and R. Sieg-wart, “Driving on point clouds: Motion plan-ning, trajectory optimization, and terrain as-sessment in generic nonplanar environments,”Journal of Field Robotics, 2016.

[4] R. Dube, D. Dugas, E. Stumm, J. Nieto,R. Siegwart, and C. Cadena, “Segmatch: Seg-ment based loop-closure for 3d point clouds,”arXiv preprint arXiv:1609.07720, 2016.

[5] J. Nikolic, J. Rehder, M. Burri, P. Gohl,S. Leutenegger, P. T. Furgale, and R. Sieg-wart, “A synchronized visual-inertial sensorsystem with fpga pre-processing for accuratereal-time slam,” in Robotics and Automation(ICRA), 2014 IEEE International Conferenceon. IEEE, 2014, pp. 431–437.

[6] P. Bazer, “Fahrzeugumfeldsensorik: Lidar,Radar, Infrarot, Ultraschall und Video im Ver-gleich Funktionsweise, Vor- und Nachteile,Sensordatenfusion,” www.zukunft-mobilitaet.net/79615/strassenverkehr/fahrzeug-umfeldsensorik-funktionsweise-lidar-radar-

infrarotsensor-ultraschall-videosensor/,[Online]; accessed 15 February 2017.

[7] R. Dube, D. Dugas, E. Stumm, J. Nieto,R. Siegwart, and C. Cadena, “Segmatch: Seg-ment based place recognition in 3d pointclouds,” 2017.

[8] M. Bloesch, S. Omari, M. Hutter, and R. Sieg-wart, “Robust visual inertial odometry usinga direct EKF-based approach,” in IntelligentRobots and Systems (IROS), 2015 IEEE/RSJInternational Conference on. IEEE, 2015,pp. 298–304.

[9] R. Mur-Artal and J. D. Tardos, “ORB-SLAM2: an Open-Source SLAM System forMonocular, Stereo and RGB-D Cameras,”arXiv preprint arXiv:1610.06475, 2016.

[10] W. Hess, D. Kohler, H. Rapp, and D. An-dor, “Real-time loop closure in 2D LI-DAR SLAM,” in Robotics and Automation(ICRA), 2016 IEEE International Conferenceon. IEEE, 2016, pp. 1271–1278.

[11] U. Graf, “SERVO,”www.github.com/grafue/SERVO, [Online];accessed 18 February 2017.

[12] J. M. Snider et al., “Automatic steering meth-ods for autonomous automobile path track-ing,” Robotics Institute, Pittsburgh, PA, Tech.Rep. CMU-RITR-09-08, 2009.

[13] J. Kong, M. Pfeiffer, G. Schildbach, andF. Borrelli, “Kinematic and dynamic vehiclemodels for autonomous driving control de-sign,” in Intelligent Vehicles Symposium (IV),2015 IEEE. IEEE, 2015, pp. 1094–1099.

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 10

Authors

Nikhilesh Alatur currently studies me-chanical engineering with a focus onRobotics at ETH Zurich in his final bach-elor semester. In the project he worked onvehicle simulation, path following and lowlevel control.

Nicholas Bunger is a final-year bachelorstudent in mechanical engineering at theETH Zurich and is responsible for the Sys-tem Engineering and Telemetry in Project-ARC.

Robin Deuber studies mechanical engi-neering BSc in his final year at ETHZurich. His study focus lies on controlsystems and robotics. In the project ARChe is responsible for control, actuation andsafety.

Renaud Dube completed his Bachelor andMaster at the University of Sherbrooke inCanada. He is currently PhD student at theETH Zurich and focuses on 3D perceptionfor autonomous vehicles using laser rangefinders.

Niklas Funk is a final-year bachelor stu-dent in Electrical Engineering at ETHZurich and will start with the master’s pro-gramme in Robotics, in fall 2017. Heworked on Project-ARC’s State Estimationand Interface as well as on the electricalsupply of all Sensors, Actuators and Com-puter Hardware.

Frederick Gonon studies mechanical engi-neering in the 6th semester at ETH Zurich.He was responsible for the electric steering& braking system and for the constructionof the sensor mount as well as the low-levelvelocity control. In his bachelor thesis hedeveloped a dynamic vehicle model for alaunch control to maximise the accelera-tion and stability of the car.

Raghav Khanna is a PhD student inRobotics at ETH Zurich and focuses onperception and mapping for autonomousaerial vehicles using visible and multi-spectral cameras.

Nico Messikommer studies mechanical en-gineering in the 6th semester at ETHZurich. During Project ARC, he workedon the implementation of a localisation &mapping based state estimation as well asthe development of an obstacle detection.

Julian Nubert is a final-year bachelor stu-dent in electrical engineering at the ETHZurich and has his responsibilities in theLocalisation & Mapping, State Estimationand Sensors & Electronics in Project-ARC.

Moritz Patriarca is a mechanical engineer-ing student in his final year at ETH Zurich. In the project ARC he is responsible forcontrol, actuation and safety.

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 11

Mark Pfeiffer completed both his Bache-lor and Master degree at ETH Zurich. Af-ter having completed his Masters thesis atUC Berkeley he is currently pursuing hisPhD at the Autonomous Systems Lab atETH Zurich, focusing on motion planningand leveraging learned motion models forground robot navigation.

Simon Schaefer studies mechanical engi-neering BSc at the ETH Zurich, focussingRobotics and Control. In Project ARC he isresponsible for State Estimation and High-Level interfaces as well as team leader.

Dominic Scotoni studies mechanical engi-neering BSc in the 6th semester at the ETHZurich. He was responsible for the con-struction of the sensor mount and the elec-tric steering & braking system as well asthe low-level velocity control of the car. Inhis bachelor thesis he developed a modelbased launch control to maximise the ac-celeration and stability of the car.

Roland Siegwart (born in 1959) is direc-tor of the Autonomous Systems Lab (ASL)of the Institute of Robotics and IntelligentSystems at ETH Zurich in Switzerland anda well known robotics expert. He was bornin Lausanne and grew up in the Canton ofSchwyz.

Erik Wilhelm earned his Bachelor andMaster in Chemical Engineering at theUniversity of Waterloo. His Dr. Sci-ETHZurich was conferred in Vehicle Designwith an emphasis on mathematical model-ing and simulation in 2011. He is currentlythe Lead Data Scientist at Kyburz Switzer-land.

EVS30 International Battery, Hybrid and Fuel Cell Electric Vehicle Symposium 12