Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator...

8
Construction Site Navigation for the Autonomous Excavator Thor Daniel Schmidt Robotics Research Lab Computer Science Technical University Kaiserslautern 67655 Kaiserslautern,Germany Email: [email protected] Karsten Berns Robotics Research Lab Computer Science Technical University Kaiserslautern 67655 Kaiserslautern,Germany Email: [email protected] Abstract—The paper at hand is part of the autonomous excavator project Thor (Terraforming Heavy Outdoor Robot) who’s goal is the development of a construction machine which performs landscaping on a construction site without an operator. So far the project mainly focused on the local excavation on one position. Due to the high digging forces the machine permanently changes its position during excavation. Furthermore, the global goal is to shape the complete construction site. Therefore, a final test platform needs to permanently reposition itself on the site. Within this paper the construction site navigation function is described which guarantees safe traveling from one pose to another one. It is based on an extended A * path planning algorithm, executed on a 2D gridmap including region growing for obstacles, including forward and backward movement. In combination with an intelligent path following algorithm the machine proved to safely reach its position with the desired orientation. I. I NTRODUCTION On larger, modern construction sites or in daylight mines for gravel, coal, or sand, the work is dominated by large construction machines. They are usually operated by human beings under relatively harsh environmental conditions. Recent works measuring the productivity per day show that even skilled operators have a tremendous decrease in workload during the day due to fatigue and stress factors [6]. The cyclic operational style of the whole operation further de- grades the driver’s concentrativeness and leads to tiredness. An autonomous machine would be able to continuously perform cyclic operations like mass excavation, material transport, or large scale landscaping without these degradation factors. In case active sensor systems are used, which are independent from light conditions, the machine could operate almost 24 hours per day. Operation in hazardous environments which are polluted by radiation or toxic waste, can be performed without the possibility to harm human beings. So far the main focus of the project laid in the automation of the local excavation process within bucket range of the machine. The perception part consists of gathering 3D pointclouds of the machine surrounding via laser scanners [20], surface extraction algorithms, truck pose detection, and excavation and dump position finding. A behavior-based control approach was chosen [15] which already proved its applicability in dynamic and unstructured outdoor domains [2], [17]. It is both used for low-level control implementing an inverse kinematics solver [14] and high-level creation of collision free trajectories for excavation and material movement [21]. During tests with the real machine, depicted in figure 1, it was detected that the high excavation forces lead to a slow but constant movement of the excavator, even in case of being mounted on its outriggers and shield. Furthermore, the whole landscaping area is usually larger then the configuration space (CSpace) of the machine. Therefore, a navigation function is needed which plans and executes collision free paths on the site. It was developed together with Christopher Schank in [16]. Fig. 1: Thor during an autonomous truck loading operation including excavation pose finding and truck detection. The maximum speed on a construction site is restricted to a few kilometers per hour, the traveling distances are only within a few hundred meters, and usually no paved roads and signs exist. As precision during movement, especially in reaching the target position including orientation (pose) plays a very important role, and very narrow passages might have to be passed, the solutions for autonomous cars are often optimized towards different aspects. For example in [18] the intermediate waypoints for the up to 175-miles long track were set in such a manner that no global path planning was required. The task mostly consisted of of high-speed road finding, obstacle detection, and avoidance. Also the tentacle approach presented in [10] is mostly suitable for local path optimization at higher

Transcript of Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator...

Page 1: Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator Thor ... solver [14] and high-level ... for path planning on grid maps is presented

Construction Site Navigation for the AutonomousExcavator Thor

Daniel SchmidtRobotics Research Lab

Computer ScienceTechnical University Kaiserslautern

67655 Kaiserslautern,GermanyEmail: [email protected]

Karsten BernsRobotics Research Lab

Computer ScienceTechnical University Kaiserslautern

67655 Kaiserslautern,GermanyEmail: [email protected]

Abstract—The paper at hand is part of the autonomousexcavator project Thor (Terraforming Heavy Outdoor Robot)who’s goal is the development of a construction machine whichperforms landscaping on a construction site without an operator.So far the project mainly focused on the local excavation on oneposition. Due to the high digging forces the machine permanentlychanges its position during excavation. Furthermore, the globalgoal is to shape the complete construction site. Therefore, afinal test platform needs to permanently reposition itself on thesite. Within this paper the construction site navigation functionis described which guarantees safe traveling from one pose toanother one. It is based on an extended A* path planningalgorithm, executed on a 2D gridmap including region growingfor obstacles, including forward and backward movement. Incombination with an intelligent path following algorithm themachine proved to safely reach its position with the desiredorientation.

I. INTRODUCTION

On larger, modern construction sites or in daylight minesfor gravel, coal, or sand, the work is dominated by largeconstruction machines. They are usually operated by humanbeings under relatively harsh environmental conditions. Recentworks measuring the productivity per day show that evenskilled operators have a tremendous decrease in workloadduring the day due to fatigue and stress factors [6]. Thecyclic operational style of the whole operation further de-grades the driver’s concentrativeness and leads to tiredness. Anautonomous machine would be able to continuously performcyclic operations like mass excavation, material transport, orlarge scale landscaping without these degradation factors. Incase active sensor systems are used, which are independentfrom light conditions, the machine could operate almost 24hours per day. Operation in hazardous environments whichare polluted by radiation or toxic waste, can be performedwithout the possibility to harm human beings. So far themain focus of the project laid in the automation of thelocal excavation process within bucket range of the machine.The perception part consists of gathering 3D pointcloudsof the machine surrounding via laser scanners [20], surfaceextraction algorithms, truck pose detection, and excavationand dump position finding. A behavior-based control approachwas chosen [15] which already proved its applicability indynamic and unstructured outdoor domains [2], [17]. It is bothused for low-level control implementing an inverse kinematics

solver [14] and high-level creation of collision free trajectoriesfor excavation and material movement [21].

During tests with the real machine, depicted in figure 1,it was detected that the high excavation forces lead to a slowbut constant movement of the excavator, even in case of beingmounted on its outriggers and shield. Furthermore, the wholelandscaping area is usually larger then the configuration space(CSpace) of the machine. Therefore, a navigation functionis needed which plans and executes collision free paths onthe site. It was developed together with Christopher Schankin [16].

Fig. 1: Thor during an autonomous truck loading operationincluding excavation pose finding and truck detection.

The maximum speed on a construction site is restricted to afew kilometers per hour, the traveling distances are only withina few hundred meters, and usually no paved roads and signsexist. As precision during movement, especially in reachingthe target position including orientation (pose) plays a veryimportant role, and very narrow passages might have to bepassed, the solutions for autonomous cars are often optimizedtowards different aspects. For example in [18] the intermediatewaypoints for the up to 175-miles long track were set insuch a manner that no global path planning was required. Thetask mostly consisted of of high-speed road finding, obstacledetection, and avoidance. Also the tentacle approach presentedin [10] is mostly suitable for local path optimization at higher

Page 2: Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator Thor ... solver [14] and high-level ... for path planning on grid maps is presented

velocities.

A global map of the site including travel paths is usuallycontained inside the compulsory construction plan, which de-livers enough data for optimized global path planning. Previousworks like [11] propose a hybrid of genetic algorithms (GAs)and particle swarm optimization for global path planning.Genetic Algorithms (GAs) are based on evolutionary principlesand use mutation and crossover operators to find an optimalsolution according to a fitness function in a population ofsolutions. Although GAs are good at finding near-optimalsolutions, their convergence speed is low, due to the fact thatno memory about previous solutions is retained. A fast methodfor path planning on grid maps is presented in [12]. The paperpresents a hierarchical approach that nonetheless results innear-optimal paths. In the first of two steps, a grid map withlower resolution than the input grid map is created, dubbedblock map, by merging each k × k patch of grid cells into ablock. If all the grid cells within a block are occupied, thenthe block is also set to be occupied, otherwise it is set tobe free. The paper presents an equation to find a value for ksuch that the occupancy structure of the grid map is preserved.Then a block path is found by A* [9] search in the block mapbased on 8-connectivity. This block path is then augmented byadding the adjacent blocks for all diagonal block pairs in thepath. The second step is to run A* search on the grid mapbut restricting it to the cells that are contained in the blockpath, which greatly reduces the search space. The result isa very fast search algorithm based on A* that can find near-optimal solutions. Another way to increase the performance ofA* search on grid maps was developed in [8]. Using so calledjump points only nodes useful for finding a path are expanded,instead of expending all nodes as A* does. It is also proved thatthis method always finds the optimal path. [13] takes anotherapproach to path planning. Their proposal is a method basedon potential field to "push" the path away from obstacles whilestill trying to find a smooth path. As global knowledge aboutthe construction site is known, an extended A* approach seemsto be suitable for the construction site.

The second part of the work deals with the path trackingproblem. [7] describes a simple pure pursuit steering controllerfor path tracking, as well as online obstacle avoidance. Usinga look-ahead point with distance ld from the current rearaxle position it is possible to to find the angle α betweenthe vehicle’s heading vector and the look-ahead vector. Thisis then used to determine an appropriate steering angle. [3]presents B-Spline path creation from waypoints as well as apath tracking algorithm. The latter one uses the heading andposition information of a given point on the spline to calculatecontrol inputs, angular velocity and linear velocity to steer therobot along the path. Aside from online trajectory generation[5] presents a steering controller which enables a robot withAckermann kinematics to follow a B-Spline curve. In fact thelateral controller developed for that paper can follow any typeof trajectory as long as it is possible to calculate a headingand a lateral error.

In the following section the used path planning approachwill be presented. Afterwards section III shows the imple-mented path tracking approach, followed by experimentalresults in section IV. Finally, a conclusion and short outlookis given in section V.

II. PATH PLANNING

For the autonomous driving functions, an extended path-planning approach was chosen, as travel paths on a construc-tion site are usually fixed and have to be used. This meansthat the software first plans the paths, based on a suitable maprepresenting the environment, using a global path planningalgorithm, and then executes these paths. A binary grid mapwas chosen, which means that each cell can only be in thestate occupied or forbidden, denoted by a boolean true, or free,denoted by false. To handle uncertainty concerning obstacleshapes, which evolves from sensor errors and noise, a regiongrowing approach is used to artificially increase the size ofoccupied cells. This implicitly forces pathfinding algorithms tokeep a minimum safe distance from obstacles. Until the desiredgrowth is reached, the algorithm cyclically finds all neighborsof occupied cells and sets them to occupied. Algorithm 1 showsa pseudo-code version of this method and figure 2 shows anexample of this method applied to a grid map.

input: A grid map map

for i← 0 to desired growth dooccupied cells = FindAllOccupiedCells(map);foreach cell in occupied cells do

neighbors = GetEightNeigboursOfCell(cell);foreach cell in neighbours do

cell.occupied = true;end

endend

Algorithm 1: Region growing algorithm

Fig. 2: Example of one iteration of region growing usingthe algorithm 1 with originally (black) and grown (orange)cells [16].

For the pathfinding itself, the well known search algorithmA* was used. It was first described by [9] in 1968 and isan extension of the famous Dijkstra’s algorithm that achievesfaster searches using heuristics. There are a lot of additionalimprovements for A* search on uniform grid map, for examplegraph pruning as described in [8]. However, simply usingA* ignores the robots kinematics for turning, forward, andbackward movement. Therefore, this paper proposes to solvethe pathfinding problem using a series of states to reach a targetposition. A state consists of three items position, orientation,and direction. The position are coordinates on the grid mapand orientation is represented in 45 steps denoted by compassdirections. Driving direction is used to designate whether therobot is driving forward or in reverse. The grid map is usedto construct a graph of these states, where occupied cells are

Page 3: Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator Thor ... solver [14] and high-level ... for path planning on grid maps is presented

East Northeast North Nortwest

West Southwest South Southeast

Fig. 3: Child states from a given state with forward (blue) andbackward (red) arrows [16].

represented as unreachable states. Each state has several childstates, shown in figure 3, which are dependent on the currentposition, orientation and driving direction. Using these statesinstead of a simple grid map provides several benefits. Thekinematic restrictions of the robot are taken into account tosome degree and it is possible to find a path to not only aspecific target position but also to a specific target orientation.In addition to that, the algorithm can find paths that includemaneuvers to get into a better position or orientation, indicatedby changes in the driving direction. The paths can be adjustedby changing the costs to traverse from cell to cell. In thisstate space, there a several types of transitions, each withtheir own cost attached to them. Some possible transitions aredriving forward, driving backward, changing direction whiledriving forward, changing into reverse, and changing intodriving forward. To prefer forward driving and remaining inthe current direction, the costs for backward movement anddirection change are quite high.

Using these states to distinguish orientation and drivingdirection, has the negative side effect of increasing the searchspace for A*. In order to improve performance, a hierarchicalapproach similar to the one in [12] is chosen. Instead ofrunning the search algorithm on a coarse map and then usingthe results to run it again on the input map, it is just executedonce on a coarse map. This is possible as the kinematicrestrictions of the robot make a 45 turn within 1m impossible.Instead, the algorithm runs on coarse blocks that are set tobe occupied if any of the underlying cells is occupied. Thisreduces the search space and provides better paths more in linewith the robots capabilities.

Reducing the resolution of the map leads to new problems.If the start or target position lies inside an occupied block, itdoes not necessarily mean that the position is unreachable.In fact, the cell corresponding to the start or target positioncould be free, but some of the other cells in its neighborhoodcause the entire block to be marked as occupied. The solutionproposed for this problem is to take a closer look at the patchof cells corresponding to the block as depicted in figure 4.If the position inside an occupied cell is free it might bereachable. In order to determine its reachability the patch ofcells is divided into eight sections, marked by the blue linesin figure 4b, centered around the position which is marked bythe red circle. If one of the cells in a sector is occupied, theblocks neighboring that sector are set to be occupied, whichis indicated by the arrows in the image. In a final step, the

(a) (b) (c)

Fig. 4: (a) The target position (red circle) is inside an occupiedblock. (b) Only a few cells in the block are actually occupied.The block is divided into sectors (blue lines), which are used todetermine which neighboring blocks should be set to occupied.(c) The target block is unoccupied and the obstacles from thegrid cells were moved to the neighboring blocks [16].

original block is set to free, which means the target position isnow approachable from all directions that do not intersect withan obstacle on the grid map, or in case of the start position,allow the robot to leave that block without encountering anobstacle.

Fig. 5: Illustration of the al-ternate target poses used toreduce the orientation errorat arrival. The dots in frontand behind the arrow are thealternate targets [16].

Fig. 6: Checking if the targetposition is in front or behindthe robot [16].

First experiments with this algorithm showed that althoughthe position accuracy was good, the orientation at the targetposition was often far from the desired orientation. In orderto improve the orientation accuracy, a new artificial goalposition in front or behind the target position was set. Now thepathfinding algorithm has to be used two times, searching for apath to a position behind the robot when driving forward at thatfinal position, and vice versa for backward movement depictedin figure 5. This enhancement reduced the orientation error atthe target pose while simultaneously solving the problem ofstart and target position being in the same block on the mapby giving the search algorithm a new target pose.

The last improvement made was dubbed trivial path plan-ning. Because of the introduction of the coarse map, thepathfinding algorithm does not produce good results whenasked to find a path to a position only a few meters ahead orbehind of the bucket excavator. Trivial path planning consistsof first checking if the target position is in front or behind therobot (see figure 6), determined by an opening angle, and thenchecking if there are any occupied cells on the straight line inbetween the starting and target position.

Page 4: Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator Thor ... solver [14] and high-level ... for path planning on grid maps is presented

Afterwards, trajectory generation transfers the sequence ofstates into a B-spline. First, simplification is performed byremoving segments of the sequence that represent driving ona straight line, as shown in figure 7.

(a) (b)

Fig. 7: (a) Forward (blue) and backward (red) paths beforeremoval of redundant nodes. (b) Paths after simplification [16].

Then the state sequence is separated into several segmentsaccording to the driving direction. This means a change inthe driving direction indicates the start of a new segmentof the path. After this step the states are converted intoposes using the mapping between the grid map and the realworld coordinates. The first pose in the first path segment isreplaced by the current robot pose and the desired target poseis added to the back of the last path segment. This ensuresthat the trajectory starts from the robots current pose andreaches the target pose instead of the alternate target poseused for the pathfinding. To ensure a more smooth transitionbetween trajectory segments, the orientation at the last pose ofa segment is adjusted to match the orientation of the first posein the next segment. In summary, the post-processing of theA* state-path results in a number of path segments consistingof poses, in which the driving direction alternates betweendriving forward and backward. The generation of the B-splinetrajectory is very similar to the spline generation in [3]. Then + 1 poses from a path segment are used as waypoints Qk

which the spline has to interpolate. For that, the tangents at thewaypoints have to be known (see figure 8). Equations 1 areused to create the tangent vectors

−→T1 to

−−−→Tn−1. It is possible

for the denominator in the equation for α to be 0 undercertain conditions. If this happens, α is set to 1

2 which implies

Fig. 8: Determining a waypoints tangent direction from neigh-boring waypoints taken from [3].

−→Vk = 1

2 (−→qk +−−→qk+1). This means, in that case the tangent vectoris the average of the two vectors between the waypoints. [3]provides special equations to guess the tangents T0 and Tn,however the path segments already contain the orientation inthese points and this information is used in equations 2.

−→qk = Qk −Qk−1, k = 1, · · · , n−→q0 = 2−→q1 −−→q2

−−→qn+1 = 2−→qn −−−→qn−1

αk =|−−→qk−1 ×−→qk |

|−−→qk−1 ×−→qk |+ |−−→qk+1 ×−−→qk+2|, k = 1, · · · , n− 1

−→Vk = (1− αk)−→qk + αk

−−→qk+1, k = 1, · · · , n− 1

−→Tk =

−→Vk

|−→Vk|

, k = 1, · · · , n− 1

(1)−→T0 =

(cos(start.Y aw)sin(start.Y aw)

)−→Tn =

(cos(end.Y aw)sin(end.Y aw)

) (2)

In order to construct a cubic Bézier segment between eachwaypoint pair Qk and Qk+1, two other control points arerequired. The Bézier control points are denoted by Pk,i inthe following, as listed in equation 3. By iterating overk = 0, · · · , n − 1 and using the equations in 4, 5, and 6 therequired control points are calculated for each segment. Thenequation 7 is used to calculate the parameter range.

Qk = Pk,0 Pk,1 Pk,2 Pk,3 = Qk+1 (3)

a = 16− |−→Tk +

−−→Tk+1|2

b = 12(Pk,3 − Pk,0) · (−→Tk +

−−→Tk+1)

c = −36|Pk,3 − Pk,0|2(4)

α =−b+

√b2 − 4ac

2a(5)

Pk,1 = Pk,0 +1

3α−→Tk Pk,2 = Pk,3 −

1

3α−−→Tk+1 (6)

u0 = 0

uk+1 = uk + 3|Pk,1 + Pk,0|(7)

This algorithm results in n Bézier segments with the parameterrange [uk, uk+1] between each waypoint pair. These controlpoints and parameters are then used to create a B-spline curve.The control points for this curve are shown in equation 8 andthe knot vector is shown in equation 9. The sequence of theseB-spline curves together with information about the drivingdirection is then passed along to the path tracker.

Q0, P0,1, P0,2, P1,1, P1,2, · · · , Pn−2,2, Pn−1,1, Pn−1,2, Qn (8)

U =

0, 0, 0, 0,

u1

un,u1

un,u2

un,u2

un, · · · ,

un−1

un,un−1

un, 1, 1, 1, 1

(9)

Page 5: Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator Thor ... solver [14] and high-level ... for path planning on grid maps is presented

de(t)

xRCS

θe(t)

l(t)

yRCS

lb + lv · v(t)

p(t)

xWCS

yWCS

Fig. 9: Parameters of the lateral controller taken from [5].

III. PATH TRACKING

The lateral controller from [5] is quite suitable for thiswork, as the goal there also was to keep a heavy machine, atractor in this case, on a planned path, while only the headingand lateral errors are needed as input for this controller towork. The parameters needed are shown in figure 9. In order todetermine these values, a point l(t) dubbed look-ahead pointis determined. This look-ahead point is used to compensatefor the delay between the commands issued by the controllerand the actual realization of these steering angles. Equation 10defines that point in the robot coordinate system (RCS), whichshould be positioned at the robot’s rear axle with the x-axis pointing forward. The variable lb is used to model staticcommunication delay whereas the factor lv is used to accountfor the fact that at higher speeds (v(t) represents the currentvelocity) the look-ahead point needs to be further away.

l(t)(RCS) = (lb + lv · v(t), 0)T (10)

In the next step, the look-ahead point in transformed intothe world coordinate system (WCS) using the current locationof the robot and then the closest point p(t) on the trajectoryspline is calculated. p(t) is the point with the shortest dis-tance from the trajectory to the transformed look-ahead point.Finding this point can be done by using the de Casteljau1

algorithm to iteratively subdivide the trajectory spline intosmall linear sections and then finding the minimum distanceto these linear sections. The lateral error de(t) is then definedas that minimum distance between p(t) and l(t)(WCS). Theheading error Ωe(t) is then calculated by using a vector thatis perpendicular to the vector from p(t) to l(t)(WCS) and thevector from the robots position to l(t)(WCS). The enclosedangle between these to vectors is the heading error Ωe(t).These two values are the errors the actual steering controller(also called lateral controller) tries to minimize. While in thisthesis and in the paper [5] B-splines are used as the trajectories,any trajectory representation from which de(t) and Ωe(t) canbe calculated could be used for the lateral controller. Thelateral controller developed in the paper and used by this thesis

1https://en.wikipedia.org/wiki/De_Casteljau’s_algorithm

is based upon the Stanley Controller [18] and is similar to aPID controller. Equation 11 calculating the steering angle isslightly adapted for this thesis by adding a signum function,as driving in reverse was originally not considered. When therobot is slowing down to a stop, v(t) is replaced by a fixedvalue in 11 because small velocities in the argument of tan−1

lead to unwanted behavior.

δ(t) = kp1·

θe(t) · sgn(v(t)) + tan−1

kp2 de(t) + ki∫ tt−T de(τ)dτ + kdd

′e(t)

v(t)

(11)

Equation 11 uses θe(t) and de(t) which describe theaveraged lateral and heading errors. These are obtained byapplying a moving averages filter to the error values. Anothermoving averages filter is applied to the steering angle output tosmooth any unwanted oscillations in the steering signal. Whilethis introduces an additional delay for the steering signal,the look-ahead point compensates this. The parameter T isused to limit the integration of the lateral error to a user-definable window instead of integrating over the whole timeframe. This avoids small lateral errors from accumulating andoverwhelming the other factors.

IV. EXPERIMENTS AND TEST RESULTS

Common driving tasks for a mobile excavator on a con-struction site, are global traveling from one position to anotherincluding obstacles, or local displacement during an excavationoperation which may also include driving backwards. The ex-periments simulating these scenarios are additionally separatedinto two categories. A first set of tests was performed usinga virtual localization sensor that measures the exact pose ofthe robot. The second category of tests uses a simulated noisyGPS (Global Positioning System) receiver and IMU (InertialMeasurement Unit). Both tests were executed within a realistic,physics based 3D simulation environment of a constructionsite as depicted in figure 10 and described in [19]. The travelpaths were recorded and visualized within a 2D gridmap,consisting of quadratic cells with a side-length of 1m, as shownin figure 12a. Black cells define obstacles after region growing,green ones the additional cells of the coarse planner, the blueline shows the planned path whereas the pink one is therecorded travel path after each test-run. The planned and realposes of the excavator are depicted by an oriented rectanglewith an arrow showing towards the front of the machine.

Fig. 11: Simple forward driving without obstacles in theway [16].

The virtual localization sensor used in the first series oftests reads the error free pose of the robot directly from thesimulation. Figure 11 shows the result of a simple test-runwith the target pose being in front of the robot without anyobstacles in the way. As can be seen in the image, the robot

Page 6: Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator Thor ... solver [14] and high-level ... for path planning on grid maps is presented

(a) (b)

(c) (d)

Fig. 10: Driving inside the simulated 3D environment fromone position (a) to another (d).

(a) (b)

Fig. 12: Distance driving around a simple shape (a) and in amore complex environment (b) [16].

reached the target position with only minimal deviation fromthe desired pose.

Figure 12a shows a more complex test-run with a targetpose far away from the start position and a simple obstacleshape. The purple curve shows the path traveled by the robot.As before, the robot managed to closely follow the trajectorycalculated by the pathfinding system and reached the targetposition with a high degree of accuracy, stopping just shortof the desired position. The next test in figure 12b has aneven more complicated environment, as it contains passageswith obstacles on both sides. The picture shows that the robotexhibits a tendency to stay at the inside of the corners but stillreached the target position without touching any of the realobstacles.

In case of local machine displacement, kinematic restric-tions make it impossible to directly drive there, and thereforerequire the inclusion of backward passages. The followingseries of tests have the goal to move sideways to a positionparallel to the original pose. This forces the robot to changeits driving direction at least once. Figure 13 shows the robotspath to a position 5m above the starting position. While therobot stopped short of the desired position, its orientation isvery close to the target. In order to test the solver in a morecomplicated scenario, the next test required the robot to moveto a position parallel to its starting position but rotated by 180.The path calculated by the pathfinding algorithms is shown

Fig. 13: Moving to a positionparallel to the original withan obstacle in front. Startingpose is black, target pose isred, robot pose is blue, and thedriven path is marked green.

Fig. 14: Path for a parallelnavigation with the target pose(red) rotated 180 relative tothe start pose (blue).

in figure 14 with the start pose marked blue and the targetpose red. The red curves are the trajectory segments wherethe robot has to drive in reverse and the blue curves designatethe segments where the robot drives forward.

To also simulate results under noisy and uncertain posi-tioning, a simple localization algorithm based on the virtualGPS receiver and IMU is used for the following tests. Whilethe position is delivered by the GPS receiver, the IMU is usedto determine the orientation of the robot. Figure 15 showsa set of parallel navigation tests with an increasing standarddeviation for the Gaussian noise signals in the virtual GPSreceiver. Figures 15a and 15b show that, although the testparameters are the same, the noisy localization can severelyaffect the results. However, all of the tests show that targetaccuracy suffers with an imprecise localization and the vehiclealways stops short of the actual target. In the test shown infigure 15d, the path controller was not able to steer the robottowards its target and aborted because it thought it reached theend of the trajectory. For maneuvering to close targets, preciselocalization seems to be a requirement.

(a) 1m position error, 0.25 ori-entation error.

(b) 1m position error, 0.25 ori-entation error.

(c) 2m position error, 0.25 ori-entation error.

(d) 5m position error, 0.25 ori-entation error.

Fig. 15: Parallel navigation with different position and orien-tation errors simulated by noisy localization signals [16].

The next series of tests were designed to study the per-formance of the system when driving longer distances with

Page 7: Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator Thor ... solver [14] and high-level ... for path planning on grid maps is presented

imprecise positioning. The first run used 1m as the standarddeviation for the error of the position. Figure 16 shows thatthere is more deviation from the path than there was with theprecise localization in figure 12b. As in the previous tests targetaccuracy is also lower. The tests shown in figures 17 and 18increase the error applied to the position which translates intomore deviation from the path. Note that the robot was still ableto reach the target with a position error of 5 meters while inthe parallel navigation test with the same error (see figure 18)it failed to execute the trajectory.

Fig. 16: 1m position error, 0.25 orientation error [16].

Fig. 17: 2m position error, 0.25 orientation error [16].

All the tests so far only contained a small orientationerror. The next ones are performed in order to determine hownoise on the orientation affects the results. Surprisingly, evenvery large errors did not significantly affect the performance.Figure 19 shows the results of a test with a Gaussian error of20 added to the orientation. The image shows that deviationfrom the path is minimal apart from the last path segmentand the robot managed to reach the target pose with goodprecision. This indicates that it is more important to determine

Fig. 18: 5m position error, 0.25 orientation error [16].

the robot’s position with high precision than to have a precisemeasurement of the orientation.

Fig. 19: 1m position error, 20 orientation error [16].

The tests presented in this section show that the pathfindingand control algorithms are able to steer the robot safely to thedesired target, even with a noisy localization. In conclusion,it can be said that the autonomous driving system developedin this thesis performs well in the simulation. However, it isdifficult to predict how these results translate into the realworld since it is unknown how the real vehicle reacts to thedriving commands.

V. CONCLUSION AND OUTLOOK

In this paper a control software was developed that allowsfor the autonomous bucket excavator Thor to move to a giventarget position and arrive there with a given target orientationwithout the need for human interaction. It was decided to use aplan based approach, meaning that the full trajectory is plannedbefore the robot actually begins to move. The path planningsystem is based upon binary grid maps and region growingwas applied to compensate for the robot’s size. Pathfindingwas done using an extended A* search, however it was notenough to simply search for a path on the grid map. One of

Page 8: Construction Site Navigation for the Autonomous … Site Navigation for the Autonomous Excavator Thor ... solver [14] and high-level ... for path planning on grid maps is presented

the requirements for the autonomous driving function was thatit should be possible to define an orientation for the robot atthe target position. The reason for including this requirementdirectly into the pathfinding was that the computed paths wouldnaturally lead to the robot being aligned with the desiredorientation and could be driven with the given Ackermannsteering of the machine. This was accomplished by discretizingthe vehicle’s orientation into eight different directions whichmeans that the search space consist of states containing thecoordinates on the grid map, the vehicle’s orientation, andthe driving direction (forward, backward). The results of thepathfinding algorithm consist of a sequence of states which cannot be used by the path tracking modules. The path trackingused for the robot requires a spline trajectory. In order tocreate such a spline, the algorithm presented in [3] was usedto calculate a B-spline. Before this step, some adjustments aremade to the state sequence. It is converted into a sequenceof two-dimensional poses (position and orientation), separatedby driving direction, and the transition between these pathsegments are adjusted to allow for smoother transitions. Thefinal result is a B-spline that describes a trajectory from astarting position to the target position that does not intersectwith any obstacles. For path tracking, it was decided to use thecontroller developed by [4] since it has already proven to befunctional. The controller tries to follow a spline, calculatingthe heading and lateral error using a look-ahead point tocompensate for delays in the steering actuators. The controllersoftware was extended to allow for driving in reverse and couldthen be used without further modifications.

In the future, several improvements could be made to thecontrol software. Driving tests with the real platform haveto be made in order to evaluate the effectiveness of theconcept and software developed during the research. Dynamicobstacle avoidance has to be added to the driving functionsto improve safety and the path tracker could be replacedwith a behavior-based controller to better integrate into theautonomous control system. Alternatively, it would be worthlooking at the possibility to change the trajectory controller’sparameters during the actual driving, giving the compensationof the lateral error a higher priority at the start and favoringthe compensation of the heading error close to the end of thepath. The autonomous driving functions will never be as goodas those of autonomous vehicles designed for this task, likefor example Ravon [1], without more hardware dedicated tothis task, but it should perform well enough for the bucketexcavator to be able to complete its work without the need ofhuman interaction.

REFERENCES

[1] C. Armbrust, T. Braun, T. Föhst, M. Proetzsch, A. Renner, B.-H.Schäfer, and K. Berns. RAVON — the robust autonomous vehicle foroff-road navigation. In Proceedings of the IARP International Workshopon Robotics for Risky Interventions and Environmental Surveillance2009 (RISE 2009), Brussels, Belgium, January 12–14 2009. IARP.

[2] C. Armbrust, T. Braun, T. Föhst, M. Proetzsch, A. Renner, B.-H.Schäfer, and K. Berns. RAVON – the robust autonomous vehicle foroff-road navigation. In Y. Baudoin and M. K. Habib, editors, Usingrobots in hazardous environments: Landmine detection, de-mining andother applications, chapter 15. Woodhead Publishing Limited, 2010.ISBN-10: 1 84569 786 3; ISBN-13: 978 1 84569 786 0.

[3] T. Arney. Dynamic path planning and execution using b-splines. InThird International Conference on Information and Automation forSustainability (ICIAFS), pages 1–6, December 4-6 2007.

[4] P. Fleischmann, T. Föhst, and K. Berns. Detection of field structures foragricultural vehicle guidance. KI - Künstliche Intelligenz, pages 1–7,2013. http://dx.doi.org/10.1007/s13218-013-0264-1.

[5] P. Fleischmann, T. Föhst, and K. Berns. Trajectory planning and lateralcontrol for agricultural guidance applications. In The 2013 ICITAJournal of Information Technology and Applications, July 1-4 2013.ISBN: 978-0-9803267-5-8, in press.

[6] B. Frank and L. S. M. Alaküla. On wheel loader fuel efficiencydifference due to operator behavior distribution. In Commercial VehicleTechnology 2012 - Proceedings of the Commercial Vehicle TechnologySymposium (CVT), pages 329–346, March 13-15 2012.

[7] L. Han, H. Yashiro, H. Nejad, Q. H. Do, and S. Mita. Bezier curvebased path planning for autonomous vehicle in urban environment.In Intelligent Vehicles Symposium (IV), 2010 IEEE, pages 1036–1042,University of California, San Diego, CA, USA, June 21-24 2010.

[8] D. D. Harabor and A. Grastien. Online graph pruning for pathfindingon grid maps. In AAAI, 2011.

[9] P. E. Hart, N. J. Nilsson, and B. Raphael. A formal basis for theheuristic determination of minimum cost paths. In IEEE Transactionsof Systems Science and Cybernetics, volume 4, pages 100–107, July 21968.

[10] M. Himmelsbach, T. Luettel, F. Hecker, F. von Hundelshausen, and H.-J.Wuensche. Autonomous off-road navigation for mucar-3. KI-KünstlicheIntelligenz, 25(2):145–149, 2011.

[11] H.-C. Huang and C.-C. Tsai. Global path planning for autonomousrobot navigation using hybrid metaheuristic ga-pso algorithm. In SICEAnnual Conference 2011, September 13-18 2011.

[12] J.-Y. Lee and W. Yu. A coarse-to-fine approach for fast path findingfor mobile robots. In Intelligent Robots and Systems, 2009. IROS 2009.IEEE/RSJ International Conference on, pages 5414–5419, 2009.

[13] E. Magid, D. Keren, E. Rivlin, and I. Yavneh. Spline-based robotnavigation. In IROS, pages 2296–2301. IEEE, 2006.

[14] S. Pluzhnikov, D. Schmidt, J. Hirth, and K. Berns. Behavior-based armcontrol for an autonomous bucket excavator. In K. Berns, C. Schindler,K. Dreßler, B. Jörg, R. Kalmar, and G. Zolynski, editors, Proceedings ofthe 2nd Commercial Vehicle Technology Symposium (CVT 2012), pages251–261, Kaiserslautern, Germany, March 13-15 2012. Shaker Verlag.

[15] M. Proetzsch. Development Process for Complex Behavior-Based RobotControl Systems. RRLab Dissertations. Verlag Dr. Hut, 2010. ISBN:978-3-86853-626-3.

[16] C. Schank. Development of the alignment and displacement functionsfor thors undercarriage. Master’s thesis, University of Kaiserslautern,October 2013.

[17] D. Schmidt, M. Proetzsch, and K. Berns. Simulation and control of anautonomous bucket excavator for landscaping tasks. In Proceedings ofthe 2010 IEEE International Conference on Robotics and Automation(ICRA 2010), pages 5108–5113, Anchorage, Alaska, USA, May 3-82010.

[18] S. Thrun, M. Montemerlo, H. Dahlkamp, D. Stavens, A. Aron, J. Diebel,P. Fong, J. Gale, M. Halpenny, G. Hoffmann, K. Lau, C. Oakley,M. Palatucci, V. Pratt, and Pasc. Stanley: The robot that won the DARPAGrand Challenge. Journal of Field Robotics, 23(9):661–692, September2006.

[19] J. Wettach, D. Schmidt, and K. Berns. Simulating vehicle kinematicswith simvis3d and newton. In 2nd International Conference on Simula-tion, Modeling and Programming for Autonomous Robots, Darmstadt,Germany, November 15-18 2010.

[20] G. Zolynski, C. Schank, and K. Berns. Point cloud gathering for anautonomous bucket excavator in dynamic surroundings. In K. Berns,C. Schindler, K. Dreßler, B. Jörg, R. Kalmar, and G. Zolynski, editors,Proceedings of the 2nd Commercial Vehicle Technology Symposium(CVT 2012), pages 262–271, Kaiserslautern, Germany, March 13-152012. Shaker Verlag.

[21] G. Zolynski, D. Schmidt, and K. Berns. Safety for an autonomousbucket excavator during typical landscaping tasks. In A. R. at al., editor,New Trends in Medical and Service Robots, volume 20 of Mechanismsand Machine Science, chapter 24, pages 357–368. Springer InternationalPublishing Switzerland, April 2014.