a hierarchical framework for long-term and robust ...a hierarchical framework for long-term and...

7
A Hierarchical Framework for Long-term and Robust Deployment of Field Ground Robots in Large-Scale Farming Stuart Eiffert, Nathan D. Wallace, He Kong, Navid Pirmarzdashti, and Salah Sukkarieh Abstract— Achieving long term autonomy of robots op- erating in dynamic environments such as farms remains a significant challenge. Arguably, the most demanding factors to achieve this are the on-board resource constraints such as energy, planning in the presence of moving individuals such as livestock and people, and handling unknown and undulating terrain. These considerations require a robot to be adaptive in its immediate actions in order to successfully achieve long-term, resource-efficient and robust autonomy. To achieve this, we propose a hierarchical framework that integrates a local dynamic path planner with a longer term objective based planner and advanced motion control methods, whilst taking into consideration the dynamic responses of moving individuals within the environment. The framework is moti- vated by and synthesizes our recent work on energy aware mission planning, path planning in dynamic environments, and receding horizon motion control. In this paper we detail the proposed framework and outline its integration on a robotic platform. We evaluate the strategy in extensive simulated trials, traversing between objective waypoints to complete tasks such as soil sampling, weeding and recharging across a dynamic environment, demonstrating its capability to robustly adapt long term mission plans in the presence of moving individuals and obstacles for real world applications such as large scale farming. I. INTRODUCTION This work is primarily motivated by recent developments in the automation of field operations for unstructured environments such as construction, mining, and agriculture [1], where the application of field robotics has the potential to automate many essential or desirable tasks that are often labour-intensive, tedious or dangerous. To achieve this, however, a number of significant challenges must be addressed, including robust motion control across a variety of terrains [2]–[4], long-term autonomy and efficiency under resource constraints [5]–[6], and safe operation around moving obstacles [7]–[8]. In this paper we propose a principled operational framework capable of handling these challenges, building upon our recent research and development activities in agricultural robotics. That said, our proposed methodology are also applicable for other domains such as mining, infrastructure, and construction. In agriculture, there are a large variety of essential tasks—including soil sampling, weeding, crop observation, and recharging—that are often dispersed widely over large geographical areas. In order to complete these tasks a robot can be required to navigate off-road environments in the The authors are with the Australian Centre for Field Robotics, The University of Sydney, NSW 2006, Australia. Stuart Eiffert and Nathan Wallace contributed equally to this work. Corresponding author: [email protected] Fig. 1: The hierarchical framework deployed in simulation, demonstrating the output of the local planner (blue) being used to update the long term plan (yellow) in order to navi- gate between mission waypoints in a dynamic environment. presence of dynamic agents such as livestock and humans. This requires the planning of longer term paths between a series of mission objective waypoints whilst ensuring the adaptability of these paths to changes in the environment. To allow the robot to efficiently travel between waypoints, any short term plan updates must be made in a way that understands how the dynamic agents are likely to move around the robot and respond to its motion. Whilst previous work has demonstrated how static and dynamic elements of an unknown environment can be learnt and mapped through explicit identification of the agents, a complete long term planner which accounts for how these agents will respond to a robot’s motion as it moves through the static world has not yet been demonstrated. In this work we detail a hierarchical framework inte- grating a dynamic perception pipeline, which learns both static and dynamic elements of an unknown environment, with a multi-level path planner and tracker. This path planner consists of a local dynamic path planner which considers the responses of nearby agents, and a longer- term, objective and energy-aware global planner, as well as an advanced receding horizon motion controller. We demonstrate this integrated framework in extensive sim- ulated trials 1 to verify its use for long term and robust autonomy in large scale farming. These trials are con- ducted in an environment which replicates terrain from 1 Due to the recent breakout of COVID-19 in Australia, our planned field validation tests were postponed and will be pursued in due course. arXiv:2006.13413v1 [cs.RO] 24 Jun 2020

Upload: others

Post on 14-Jul-2020

5 views

Category:

Documents


0 download

TRANSCRIPT

Page 1: A Hierarchical Framework for Long-term and Robust ...A Hierarchical Framework for Long-term and Robust Deployment of Field Ground Robots in Large-Scale Farming Stuart Eiffert, Nathan

A Hierarchical Framework for Long-term and Robust Deployment ofField Ground Robots in Large-Scale Farming

Stuart Eiffert, Nathan D. Wallace, He Kong, Navid Pirmarzdashti, and Salah Sukkarieh

Abstract— Achieving long term autonomy of robots op-erating in dynamic environments such as farms remains asignificant challenge. Arguably, the most demanding factorsto achieve this are the on-board resource constraints such asenergy, planning in the presence of moving individuals such aslivestock and people, and handling unknown and undulatingterrain. These considerations require a robot to be adaptivein its immediate actions in order to successfully achievelong-term, resource-efficient and robust autonomy. To achievethis, we propose a hierarchical framework that integratesa local dynamic path planner with a longer term objectivebased planner and advanced motion control methods, whilsttaking into consideration the dynamic responses of movingindividuals within the environment. The framework is moti-vated by and synthesizes our recent work on energy awaremission planning, path planning in dynamic environments,and receding horizon motion control. In this paper wedetail the proposed framework and outline its integrationon a robotic platform. We evaluate the strategy in extensivesimulated trials, traversing between objective waypoints tocomplete tasks such as soil sampling, weeding and rechargingacross a dynamic environment, demonstrating its capabilityto robustly adapt long term mission plans in the presence ofmoving individuals and obstacles for real world applicationssuch as large scale farming.

I. INTRODUCTION

This work is primarily motivated by recent developmentsin the automation of field operations for unstructuredenvironments such as construction, mining, and agriculture[1], where the application of field robotics has the potentialto automate many essential or desirable tasks that areoften labour-intensive, tedious or dangerous. To achievethis, however, a number of significant challenges must beaddressed, including robust motion control across a varietyof terrains [2]–[4], long-term autonomy and efficiencyunder resource constraints [5]–[6], and safe operationaround moving obstacles [7]–[8]. In this paper we proposea principled operational framework capable of handlingthese challenges, building upon our recent research anddevelopment activities in agricultural robotics. That said,our proposed methodology are also applicable for otherdomains such as mining, infrastructure, and construction.

In agriculture, there are a large variety of essentialtasks—including soil sampling, weeding, crop observation,and recharging—that are often dispersed widely over largegeographical areas. In order to complete these tasks a robotcan be required to navigate off-road environments in the

The authors are with the Australian Centre for Field Robotics,The University of Sydney, NSW 2006, Australia. Stuart Eiffert andNathan Wallace contributed equally to this work. Corresponding author:[email protected]

Fig. 1: The hierarchical framework deployed in simulation,demonstrating the output of the local planner (blue) beingused to update the long term plan (yellow) in order to navi-gate between mission waypoints in a dynamic environment.

presence of dynamic agents such as livestock and humans.This requires the planning of longer term paths between aseries of mission objective waypoints whilst ensuring theadaptability of these paths to changes in the environment.To allow the robot to efficiently travel between waypoints,any short term plan updates must be made in a way thatunderstands how the dynamic agents are likely to movearound the robot and respond to its motion. Whilst previouswork has demonstrated how static and dynamic elements ofan unknown environment can be learnt and mapped throughexplicit identification of the agents, a complete long termplanner which accounts for how these agents will respondto a robot’s motion as it moves through the static worldhas not yet been demonstrated.

In this work we detail a hierarchical framework inte-grating a dynamic perception pipeline, which learns bothstatic and dynamic elements of an unknown environment,with a multi-level path planner and tracker. This pathplanner consists of a local dynamic path planner whichconsiders the responses of nearby agents, and a longer-term, objective and energy-aware global planner, as wellas an advanced receding horizon motion controller. Wedemonstrate this integrated framework in extensive sim-ulated trials1 to verify its use for long term and robustautonomy in large scale farming. These trials are con-ducted in an environment which replicates terrain from

1Due to the recent breakout of COVID-19 in Australia, our plannedfield validation tests were postponed and will be pursued in due course.

arX

iv:2

006.

1341

3v1

[cs

.RO

] 2

4 Ju

n 20

20

Page 2: A Hierarchical Framework for Long-term and Robust ...A Hierarchical Framework for Long-term and Robust Deployment of Field Ground Robots in Large-Scale Farming Stuart Eiffert, Nathan

real world field trial locations, and are deployed on adynamic simulation of the University of Sydney’s Swagbotagricultural robot platform. Our contributions include (i) ahierarchical framework for the deployment of field robotsin unstructured and dynamic environments, integrating ourprior work in [2]–[8]; (ii) improvement of collision avoid-ance around dynamic agents, extending on our recent work[7] for better planning persistence; (iii) comprehensive andhigh-fidelity validation in simulation, including traversalbetween waypoints to accomplish an updated set of tasks,whilst ensuring safe and efficient planning around dynamicagents, and adhering to resource and recharging constraints;(iv) demonstration of how this framework can be used toadapt to changing resource constraints by using differentlocal planner approaches to achieve varied resource use.

II. RELATED WORK

While mobile robots have been applied to dynamicenvironments for decades [9]–[12] and see continuousimprovement with regards to their ability to plan pathsaround moving agents [7], [13]–[15], the problem of ex-tending these systems for long term deployment, with theability to update their mission objectives in real time,remains an outstanding challenge. Existing solutions inagriculture tend to focus on more structured problems suchas completing a single task in row crops or orchards [1]and do not take into consideration the difference betweenstatic and dynamic elements in their environments, limitingtheir use around livestock and people. Additionally, limitedwork has focused on long term applications that requireconsideration of resource management in path planning.

A. Resource Aware Path Planning

To best utilise mobile robotic agents—particularlyelectric-powered wheeled mobile robots (WMRs)—in off-road and large scale environments, it is necessary tobe aware of the levels of onboard resources, and theanticipated costs of performing tasks and actions in theenvironment. This is especially relevant for energy usage,which determines the robot’s range and max operationaltime and has been the topic of our previous work onmodelling the energy cost of WMR motion [5].

The development of energy-aware and efficient pathplanning methods has also received significant interest inrecent years, utilising cost models for fuel and energy usefor point-to-point and coverage path planning [17]–[20]and planning energy efficient multi-stage paths for WMRsin undulating off-road environments [6]. The problem ofachieving longer term autonomy under resource constraintsis often modelled as variants of the Orienteering Problem(OP) across numerous domains [21]–[22] with recent lit-erature exploring approaches which allow for rechargingof resources [23]–[24]. Our recent work on the OP withreplenishment (OPR) [25] presents a formulation whichcan handle multiple revisits to a number of rechargingstations distributed throughout the operating environment,while also optimising the amount of time spent recharging

to ensure tasks are completed as efficiently as possible—driven by the consideration that it is desirable for agricul-tural tasks to be completed in time.

B. Dynamic Path Planning

The ability to operate safely around moving agents iscritical for any robotic system intended for use aroundhumans or livestock. There exists significant interest inmotion prediction methods in unstructured environmentsfor dynamic path planning [13]–[16], [26], and methodsthat consider the social responses in crowds and herds[7]–[8]. However, unlike applications in more structuredenvironments such as autonomous driving [15]–[16], wherewe see local maneuver-based path planning used to updatehigher level mission planners [27]–[28]—these works havenot yet been applied to systems that require longer termautonomy, such as those addressed here.

Existing dynamic path planning methods for long termfield robot autonomy are limited to simple collision avoid-ance systems, such as velocity obstacles [10] and potentialfields [29], which we compare against as an alternativeto the local path planning module developed here. Also,these methods are generally applied to semi-structuredenvironments, such as indoor use, rather than large scalefarming, where current implementations make use of failsafe (FS) methods which simply stop the robot, or controlits speed along a predefined path in the presence of movingindividuals. Whilst these methods allow certain operationsaround moving agents, they tend to greatly reduce theefficiency of task completion and can result in the robotbecoming stuck with no feasible path forward.

III. THE PROPOSED HIERARCHICALFRAMEWORK

Our approach combines a long term mission plannerwith a local dynamic path planner to achieve long termautonomy of a robot travelling between updated objectivewaypoints in the presence of both static obstacles anddynamic agents. This framework: (1) utilises our prior workin energy efficient path planning [5]–[6] for generatinglong term plans; (2) integrates this with our prior work onusing Generative Recurrent Neural Networks (GRNN) andMonte Carlo Tree Search (MCTS) [7]–[8] as a local pathplanner; and (3) adopts online, slip-compensating RecedingHorizon Motion Control (RHMC) [2]–[4] path tracking.Additionally, our framework generates a real-time updatedmap of static obstacles and traversable terrain in theenvironment, used both by the local dynamic planner andby a FS collision avoidance module. Fig. 2 outlines howeach component integrates into the hierarchical framework,with the output of the local, long term and fail safe plannersbeing passed to a high level controller.

A. Long Term Mission Planner

The long term mission plan is generated from a set ofperiodically updating, externally provided mission objec-tive waypoints which must be visited for the completion

Page 3: A Hierarchical Framework for Long-term and Robust ...A Hierarchical Framework for Long-term and Robust Deployment of Field Ground Robots in Large-Scale Farming Stuart Eiffert, Nathan

High LevelController

Long Term Planner

Local Dynamic PlannerObject Detection and Tracking

Static Mapping

RGBCameras

LIDAR

GPS

IMU OctoMapStatic Filtering

Ground segmentation

3D clustering and tracking

2D object detection

3D object association

External Mission

Objectives

Motor

Controller

Heirarchical

ModeSwitcher

Online Plan Update

Offline Optimal Planner

GRNNMotionModel

MCTS

Planner

Failsafe Collision

AvoidanceNonlinear

RHEC

Path Tracking

Local Goal

Fig. 2: System overview of the hierarchical framework, illustrating the communication between each planner, the failsafecollision module, and the high level controller. Mission objectives are provided externally to the long term planner.

of tasks such as weeding, soil sampling and recharging ofthe robot. These target locations are then connected intoa Probabilistic Roadmap (PRM) which describes a set ofkinematically feasible paths for the robot over the envi-ronment. The minimum energy paths between all pairwisecombinations of locations—calculated using the energycost of motion model developed in [5]—are used to gen-erate a ‘goal graph’, over which an asymmetric travellingsalesman problem is solved to yield the optimal orderingof visits and the corresponding energy-minimising globalplan. The approach in this paper builds upon our workin [6] by constraining the robot to operate in Ackermannconfiguration, thereby forbidding motion in any directionswithout adequate perception coverage for the sake of safety.Each sample pose in the PRM was therefore connectedby Clothoid curve segments, to generate a continuouscurvature path that is easily trackable by such a vehicle.

B. Object Detection and Static Mapping

The differentiation of traversable terrain, static obstaclesand dynamic agents is another essential element requiredfor long term autonomy in unstructured environments.Whilst this problem has been addressed in more structuredapplications such as on road autonomous vehicles, it re-mains a significant challenge in unknown and unstructuredterrain such as is often encountered on farms. In this workwe apply a multimodal perception system that combines 3DLIDAR and 2D RGB vision to both detect dynamic agentsand learn a static map of the robot’s environment. Thispipeline involves the identification of ground sets withinthe pointcloud and clustering of non-ground sets, based onwork from [30], and then association of these clustered3D sets to 2D detected bounding boxes within the cameraframe. This is achieved through the use of a Single ShotMulti-Box Detector (SSD) CNN [31] and accurate calibra-tion of the 2D and 3D sensors [32], which allows projectionof the 3D sets into the 2D frame for nearest neighbourassociation with the 2D bounding boxes. Intersection overunion is also computed between all 2D bounding boxes andthe minimal fit bounding box for projected 3D sets, whichis used to validate the association and provide a classwiseprobability score. The remaining non-associated 3D sets

are passed to a probabilistic OctoMap framework [33] forthe continuous updating of a map of static obstacles andtraversable terrain. This map is used for fail safe collisionavoidance and as an input to our MCTS dynamic pathplanner, constraining the search space.

C. Local Dynamic Planner

The local path planning module used in this work isadapted from our prior work using GRNNs and MCTSfor planning in dynamic environments [7]. This planneruses a learnt model of social response to predict crowddynamics during planning across the action space and hasbeen modified in this paper for improved persistence ofpaths between planning iterations, and to better accountfor collisions between the robot and dynamic agents incontinuous time between discrete planning timesteps. Thissection details the specific implementation of our GRNNand MCTS local path planner, however the hierarchicalframework has been designed to be agnostic with regards tothe specific local path planner used, as demonstrated by ourcomparison of various local path planners in Section IV.

1) Predictive Model: Our local planner uses a learntmodel of social response, predicting the future motion ofeach agent based on an observation of its past motion andthe known robot’s motion from the same time period, aswell as using the planned future action of the robot asinput. This model is based on our prior work [7], andsimilarly uses the robot’s position at the next timestep torepresent its current intended action. The predictive modelconsists of a recurrent Encoder-Decoder framework usinglong short-term memory (LSTM) layers, where the outputof the Encoder becomes the state of the root node usedby the MCTS planner, as detailed in Section III-C.2. TheDecoder is then used by the MCTS at each simulationstep as a state transition model. Training of this modelis performed as per [7], using generated trajectories ofinteracting agents modelled using the Optimal ReciprocalCollision Avoidance (ORCA) motion model [12].

2) Sampling Based Planner: An adapted MCTS isused to search the robot’s future action space to findthe sequence of actions that minimises the cost shown inEq. 1, where Rt refers to the robot’s position at time t,

Page 4: A Hierarchical Framework for Long-term and Robust ...A Hierarchical Framework for Long-term and Robust Deployment of Field Ground Robots in Large-Scale Farming Stuart Eiffert, Nathan

G is the local goal position, N is the total number ofagents currently observed by the robot and U refers tothe uncertainty of agent i’s estimated position at the futuretimestep t within the search. This value is determined fromthe 2D Gaussian prediction for the agent’s position at t,as detailed in [7]. α is a scaling parameter based on thedistance between Rt and the agent’s position Xt

i , as shownin Eq. 2. A value of 0 is used for α when the agent isbeyond a distance threshold of d, which is set to 3m forall experiments.

This approach extends the Parallel Single Step Simu-lation MCTS detailed in Alg. 1 of [7] for improved per-sistence of plans between timesteps. Before each planningstep, we check if the computed tree from the prior stepcan be reused to seed the current search. A comparisonis made between the current observed state, and the childnode from the last tree’s root node which best matches theactual action taken by the robot over the last timestep.

If the positions of all nearby agents within a distancethreshold of 2d of the robot’s position in the root nodeare within an error ε, equal to twice the expected sensornoise standard deviation (0.25m), we reuse the values ofthe node’s tree to seed our current root. The reused valuesare scaled by a factor of γ, determined by Eq. 3, where Mis the number of agents within the 2d distance threshold,and P t

i is the current predicted position of agent i.

Cost = (Rt −G)2 +N∑i

αU ti (1)

α =

{1

Xti−Rt , if Xt

i −Rt ≤ d0, otherwise

(2)

γ = (

M∑i

ε− |Xti − P t

i |ε

)/2M (3)

Additionally, we extend the MCTS planner to betteridentify invalid actions with regards to collisions withboth the static map, and dynamic agents between discretetimesteps. Similarly to [7], our MCTS planner uses a staticmap, detailed in Section III-B, to constrain the action spaceof the robot, which has been dilated by the radius ofthe robot. Valid actions are determined as those that donot cause a collision between the robot and the dilatedmap, or the robot and the position of each agent dilatedby the sum of the robot’s radius and the average agentradius. We extend this by comparing the straight line pathconnecting the robot position in parent and child nodes oftwo subsequent timesteps, ensuring that this line does notintersect either the contour of a static obstacle, or any otherline connecting the predicted positions of dynamic agentsin the same two timesteps.

D. High Level Control and RHMC

As in our prior work [2]–[4], a receding horizon estima-tor (RHE) is adopted to provide an estimate of the robotstate and slip conditions of the terrain. Then, based on the

proximity to detected dynamic agents and static obstacles,a hierarchical mode switching module—a crucial elementin the integration of the global optimal planner and thelocal dynamic planner—determines whether to source thelocal reference trajectory from the dynamic planner, or tofollow the online update of the global path provided bythe long term planner. In the absence of obstacles, thedefault path tracking behaviour will compute a referencebased on the robot’s progress along the global path andthe specified nominal speed. If a dynamic agent or staticobstacle is detected within the planning area, the localdynamic planner will be engaged.

The chosen path is then passed to the RHMC module,which solves the nonlinear optimisation problem to de-termine the set of control actions necessary to track thedesired path over the forward horizon. This module alsocompensates for the impact of varying slip conditions in theunderlying terrain which may otherwise adversely impactthe robot’s motion, and potentially risk a collision with anobstacle or dynamic agent.

As the local planner operates with a planning timestep ofapproximately 300ms we also make use of a FS collisionavoidance module, ensuring that the robot is able to re-flexively react to rapid changes in its environment withouthaving to wait for the local planner to complete planning.

IV. EXPERIMENTS

This section presents extensive and high-fidelity simu-lation studies to validate the performance of our proposedframework, conducted over a large set of generated prob-lem scenarios. Each scenario involves the robot departingfrom and returning to a recharging station, while being ex-ternally provided with a set of mission objective waypoints.Between 5–12 waypoints are randomly selected with anaverage spacing of 25m. The robot is also provided withan elevation map of the terrain, provided externally fromaerial LIDAR data. The robot must initially plan a longterm path offline that visits every waypoint, whilst ensuringthat the energy constraints of the robot are adhered to byreturning to the recharging station as required.

In each of these generated scenarios, we have comparedour framework as shown in Fig. 2 to a version in whichthe local planner has been replaced with either a potentialfield (PF) based approach, as described in [7], or with noplanner, instead relying only on the FS Collision Avoidancemodule. We simulate dynamic agents in each scenario,interacting with the robot as it navigates to various way-points, and have repeated all scenarios with changes toparameters such as agent density and required positionalaccuracy at waypoints, as described in the sequel.

Furthermore, as outlined in Section III-A, the robot hasbeen kinematically constrained to operate in Ackermannconfiguration for the purpose of ensuring that motion isonly possible within the forward facing planning areadictated by the field of view of the robot’s sensors. Thisis necessary to ensure that Swagbot—a platform withomnidirectional motion capabilities—does not move in

Page 5: A Hierarchical Framework for Long-term and Robust ...A Hierarchical Framework for Long-term and Robust Deployment of Field Ground Robots in Large-Scale Farming Stuart Eiffert, Nathan

Fig. 3: Example generated scenario showing offline com-puted paths for 3 iterations, each using a different type ofwaypoint with required positional accuracies of 5, 2 and1m. Each plan begins and ends at the recharging station,with required accuracy of 0.5m, to adhere to the energybudget. These plans are computed for real world terraingenerated from the Sydney University farm at Bringelly.

any directions not covered by the sensor footprint, whereit would otherwise risk damaging or injuring property,livestock or personnel.

A. Benchmark Scenarios

We evaluate our approach using varied types of missionwaypoints, each with different positional accuracy require-ments for the robot. These include:

• Observation Waypoint: 5m Accuracy• Soil Sampling Waypoint: 2m Accuracy• Weed Spraying Waypoint: 1m accuracy• Recharging Station: 0.5m accuracyEach generated scenario requires visiting a number of

waypoints of a single type, whilst ensuring that the robotreturns to a recharging station within its energy budget.Upon recharging, an updated set of waypoints is providedto the robot—consisting of either observing, sampling, orweeding tasks—and the robot begins again. This iterationis repeated 8 times for each scenario. We measure perfor-mance using the following metrics:

1) Deviation from the optimal path;2) Average speed to reach each waypoint;3) Number of near-collisions with dynamic agents.The optimal path connecting each node along the robot’s

longer term plan is determined by the offline planner asdescribed in Section III-A. The average speed to reach awaypoint is determined by distance of the waypoint at thetime that the robot receives it as its next goal, over thetotal duration required for the robot to achieve the requiredpositional accuracy for that type of waypoint.

B. Implementation

These agents are simulated using the ORCA [12] model.They are spawned at random locations between waypoints

for each scenario and are assigned similarly random goalpoints to travel towards at speeds ranging from 0.1–1.5m/s. For all scenarios, agents are simulated with a radiusof 0.5m and react to the robot assuming a radius of 1.5m.

The robot’s perception has been simulated to reflect thelocalisation and object detection of the real world agri-cultural robot Swagbot, described in [7]. Sensor noise hasbeen applied to the simulated GPS and IMU sensors usedfor localisation, and to the simulated obstacle detectionproportional to the distance from the robot, matching thatobserved in previous real world experiments. Simulatedterrain has been included, using information from publiclyavailable satellite data. For the purposes of these simulatedexperiments we have also assumed the availability of astatic obstacle map for use in the local planner, rather thanthe creation of one from sensor input.

We repeat each scenario for the compared methods,using either our MCTS approach, a PF planner, or onlythe FS method. Additionally, we repeat these experimentsusing two different crowd densities of 10m2 (dense) and50m2 (sparse) per agent, giving on average distances ofapproximately 3m and 7m between each agent respectively.Simulations are run in real time, taking on average 2.5hours to complete all iterations per scenario, depending onthe type of local planner used. We additionally generate 3separate scenarios for each testing variation, totalling 144iterations across all experiments and 45 hours of testing.

In terms of estimation and control, the RHMC moduleuses a horizon length of 3s, consisting of 15 samplingintervals of 0.2s, and the robot’s steering angle is con-strained to within ±40◦. The configuration of this moduleis otherwise the same as in [4]. The energy cost of motionmodel used for the global long-term planner is configuredto use the ‘Bringelly’ site configuration as defined in [5],which corresponds to the site from which the simulatedoperating environment was derived.

V. RESULTS AND DISCUSSION

Table I summarises the performance of the robot inreaching the required positional accuracy for each way-point. The % of times that the robot is successfully ableto navigate to the waypoint within timeouts of 1 minuteand 5 minutes is shown for two different agent densities,10m2/agent and 50m2/agent, simulating both a dense andsparse herd or crowd. It is clear that the choice of localplanner impacts the robot’s performance, with the failsafeonly version failing to reach weeding waypoints (1m po-sitional accuracy) in dense environments within the 1 mintimeout 28% of the time. This number drops significantlyto 8.6% in sparse environments, indicating the applicabilityof different planning methods to different environments.Versions of the framework using responsive local planners,MCTS and PF, perform well in both the sparse and denseenvironments, achieving only 2.8% failure at 1m accuracyfor MCTS and 4.6% for PF for dense environments whenrestricted to 1 minute timeout, and less than 1% failurewhen allowed to continue for up to 5 minutes.

Page 6: A Hierarchical Framework for Long-term and Robust ...A Hierarchical Framework for Long-term and Robust Deployment of Field Ground Robots in Large-Scale Farming Stuart Eiffert, Nathan

0 0.2 0.4 0.6 0.8 1 1.2 1.4 1.6 1.8 2 2.2 2.40

5

10

15

20

25

30

0.5m Accuracy

m/s

%

0 0.2 0.4 0.6 0.8 1 1.2 1.4 1.6 1.8 2 2.2 2.40

5

10

15

20

25

30

35

2m Accuracy

m/s

0 0.2 0.4 0.6 0.8 1 1.2 1.4 1.6 1.8 2 2.2 2.40

5

10

15

20

25

30

5m Accuracy

m/s

%

med. std.

1.36 0.211.11 0.220.83 0.32

0 0.2 0.4 0.6 0.8 1 1.2 1.4 1.6 1.8 2 2.2 2.40

5

10

15

20

25

30

1m Accuracy

m/s

%

0 0.2 0.4 0.6 0.8 1 1.2 1.4 1.6 1.8 2 2.2 2.40

5

10

15

20

25

2m Accuracy

m/s

%

0 0.2 0.4 0.6 0.8 1 1.2 1.4 1.6 1.8 2 2.2 2.40

5

10

15

20

25

30

5m Accuracy

m/s

%

MCTS PF FS

med. std.

0.97 0.310.80 0.300.55 0.32

med. std.

0.97 0.320.81 0.310.53 0.30

med. std.

1.36 0.271.11 0.230.77 0.32

med. std.

0.95 0.330.80 0.280.52 0.27

med. std.

1.31 0.311.01 0.230.74 0.31

Dens

eSp

arse

Fig. 4: Average speed to achieve a required positional accuracy of 5, 2 and 1m for % of waypoints tested. In both dense(top) and sparse (bottom) environments, the hierarchical framework is able to achieve the required accuracy in a shortertime using the more responsive local path planners, MCTS and PF, compared to the FS method.

Timeout Local Dense (10 m2/agent) Sparse (50 m2/agent)Planner 5m 2m 1m 5m 2m 1m

1min MCTS 0% 0.4% 2.8% 0% 0% 0.4%PF 0% 1.5% 4.6% 0% 0.5% 1.0%FS 2.4% 8.5% 28.0% 0% 3.7% 8.6%

5mins MCTS 0% 0.4% 0.6% 0% 0% 0%PF 0% 0.5% 0.8% 0% 0% 0.7%FS 0% 2.9% 9.8% 0% 0% 1.2%

TABLE I: % of failures not reaching required accuracy(5, 2m or 1m) within timeout (1min or 5min), for dense(10 m2/agent) and sparse (50 m2/agent) environments,with average distances of 3m and 7m between agentsrespectively.

Local Dense (10 m2/agent) Sparse (50 m2/agent)Planner med (m) std (m) med (m) std (m)MCTS 1.63 22.57 0.28 13.5PF 3.9 37.50 0.20 12.26FS 0.05 5.13 0.06 3.05

TABLE II: Displacement from optimal path, shown forall simulated tests, in both dense and sparse densities ofdynamic agents. Median and standard deviation are shownin metres for each tested local path planner.

A key reason for these failures was due to the robottaking evasive action, which could occasionally perturb therobot pose to an extent that made subsequently reachingthe goal region no longer kinematically feasible withouttaking a more circuitous route, which in turn increasedthe chance of further disruptions by the dynamic agents.This situation provides a clear motivation for the use ofplatforms with omnidirectional mobility—a direction weplan to pursue further with Swagbot once its sensingconfiguration supports it—as the increased mobility of sucha platform would circumvent this situation almost entirely.

Fig. 4 illustrates the average speed at which the robot

Local Dense (10 m2/agent) Sparse (50 m2/agent)Planner % coll. med (m) std (m) % coll. med (m) std (m)MCTS 4.70 2.61 1.07 0.71 3.81 1.72PF 5.07 2.54 1.00 0.62 3.78 1.78FS 3.25 2.63 0.95 1.34 3.62 1.63

TABLE III: Minimum distance to agents, for all tests, inboth dense and sparse environments. % of collisions (dist<2m) per interaction is shown with median and standarddeviation in metres for each tested local path planner.

was able to reach the required positional accuracy of eachplanned waypoint for each test (within 5m for observationwaypoints, 2m for soil sampling and 1m for weeding).The MCTS local planner implementation was able tooutperform both the PF and FS versions for all accuracies,in both sparse and dense agent densities. These resultsindicate that in the presence of dynamic agents, the timeefficiency of the system is greatly dependent on the typeof local planner used. The robot is able to completethe required mission objectives in significantly less timewhen a more responsive local planner is included in theframework. However, the results shown in Table II showthat the choice of local planner also impacts the robot’senergy efficiency. Deviation from the offline optimal pathis used as a proxy for energy use, indicating that a lessresponsive local planner—in this case the FS method usedalone—uses significantly less energy than a planner whichadapts its path to account for the motion of nearby agents.

Additionally, Table III shows that whilst all testedversions are usually able to maintain adequate distancefrom agents, with very similar median distances and stan-dard deviations for both agent environment densities, thenon-responsive FS method results in significantly morecollisions with agents in the sparse environment. Thisresult suggests that a number of collisions are due to

Page 7: A Hierarchical Framework for Long-term and Robust ...A Hierarchical Framework for Long-term and Robust Deployment of Field Ground Robots in Large-Scale Farming Stuart Eiffert, Nathan

the agents running into the robot, rather than the robothitting the agents, and can be avoided by using a moreresponsive planner in sparse environments. Conversely, inthe dense environment, the more responsive versions resultin greater number of collisions, suggesting that when theenvironment becomes too complex these methods may infact cause more collisions through their efforts to avoidan initial collision. Our results suggest that by usingvarious combinations of planners, the framework is ableto achieve different performances in varied environments,demonstrating not just the flexibility of the framework toadapt to changes in the environment, such as density ofcrowds or herds, but also to changing requirements, suchas energy usage, or speed of mission completion.

VI. CONCLUSION

This work has proposed a hierarchical framework en-abling the long-term operation of a field robot for naviga-tion of mission waypoints in dynamic environments whilstadhering to resource budgets and other operational con-straints. In particular, we have shown how this frameworkcan handle changes in the environment and in currentmission constraints, by using an adaptable local planningmodule to achieve varied performance as required. Wehave evaluated the strategy in extensive simulated trialsand demonstrated its capability to robustly adapt long termmission plans in the presence of moving individuals andobstacles for real world applications. In future work, wewill apply this framework to a robot to test its capabilityin the continuous completion of tasks such as weeding, soilsampling, and observing crops and livestock.

REFERENCES

[1] A. Bechar and C. Vigneault, Agricultural robots for field operations.Part 2: Operations and systems, Biosystems Engineering, Vol. 153,pp. 110–128, 2017.

[2] N. Wallace, H. Kong, A. Hill, and S. Sukkarieh, Receding horizonestimation and control with structured noise blocking for mobilerobot slip compensation, Proc. of IEEE ICRA, pp. 1169–1175,Montreal, Canada, 2019.

[3] N. Wallace, H. Kong, A. Hill, and S. Sukkarieh, Structured noiseblocking strategies for receding horizon estimation and control ofmobile robots with slip, Proc. of Australasian Conf. on Roboticsand Auto. (ACRA), pp. 1–10, 2018.

[4] N. Wallace, H. Kong, A. Hill, and S. Sukkarieh, Experimentalvalidation of structured receding horizon estimation and control formobile ground robot slip Compensation, Proc. of the 12th Conf. onField and Service Robotics, pp. 1–16, Tokyo, Japan, 2019.

[5] N. Wallace, H. Kong, A. Hill, and S. Sukkarieh, Motion costcharacterisation of an omnidirectional WMR on uneven terrains,Proc. of the 12th IFAC CAMS and 1st IFAC WROCO, Vol, 52, No.22, pp. 31–36, Daejeon, Korea, 2019.

[6] N. Wallace, H. Kong, A. Hill, and S. Sukkarieh, Energy awaremission planning for WMRs on uneven terrains, Proc. of the 6thIFAC AgriControl, pp. 149–154, 2019.

[7] S. Eiffert, H. Kong, N. Pirmarzdashti, and S. Sukkarieh, Pathplanning in dynamic environments using Generative RNNs andMonte Carlo tree search, Proc. of IEEE ICRA, To appear, Paris,France, 2020.

[8] S. Eiffert and S. Sukkarieh, Predicting responses to a robot’s futuremotion using generative recurrent neural networks, Proc. of ACRA,2019.

[9] D. Fox, W. Burgard, and S. Thrun, The dynamic window approachto collision avoidance, IEEE Rob. and Auto. Mag., Vol. 4, No. 1,pp. 22–33 1997.

[10] P. Fiorini and Z. Shiller, Motion planning in dynamic environmentsusing velocity obstacles, Int. Journal of Robotics Research, Vol. 17,No. 7, pp. 760–772 1998.

[11] P. Henry, C. Vollmer, B. Ferris, and D. Fox, Learning to navigatethrough crowded environments, Proc. of IEEE ICRA, pp. 981–986,2010.

[12] J. Van Den Berg, S. J. Guy, M. Lin, and D. Manocha, Reciprocaln-body collision avoidance, Proc. of the 14th Int. Symposium ISRR,Springer Tracts in Advanced Robotics, Vol. 70, pp. 3–19, 2011.

[13] M. Everett, Y. F. Chen, and J. P. How, Motion planning amongdynamic, decision-making agents with deep reinforcement learning,Proc. of IEEE/RJS IROS, 2018.

[14] C. Chen, Y. Liu, S. Kreiss, and A. Alahi, Motion planning amongdynamic, crowd-robot interaction: Crowd-aware robot navigationwith attention-based deep reinforcement learning, Proc. of IEEE/RJSIROS, pp. 3052–3059, 2019.

[15] J. Li, W. Zhan, Y. Hu, and M. Tomizuka, Generic tracking andprobabilistic prediction framework and its application in autonomousdriving, IEEE Trans. on Intelligent Trans. Systems, pp. 1–16, 2020.

[16] Y. Xing, C. Lv, and D. Cao, Personalized vehicle trajectory pre-diction based on joint time series modeling for connected vehicles,IEEE Trans. on Vehicular Tech., No. 2, pp. 1341–1352, 2020.

[17] H. Qian, G. Xu, J. Yan, T. L. Lam, Y. Xu, and K. Xu, Energymanagement for four-wheel independent driving vehicle, Proc. ofIEEE/RSJ IROS, pp. 5532–5537, 2010.

[18] Y. Mei, Y. H. Lu, Y. C. Hu, and C. S. G. Lee, Deployment of mobilerobots with energy and timing constraints, IEEE Trans. on Robotics,Vol. 22, No. 3, pp. 507–522, 2006.

[19] P. Tokekar, N. Karnad, and V. Isler, Energy-optimal trajectoryplanning for car-like robots, Autonomous Robots, Vol. 37, No. 3,pp. 279–300, 2014.

[20] M. Wei and V. Isler, Coverage path planning under the energyconstraint, Proc. of IEEE ICRA, pp. 368–373, 2018.

[21] J. Yu, M. Schwager, and D. Rus, Correlated orienteering problemand its application to persistent monitoring tasks, IEEE Trans. onRobotics, Vol. 32, No. 5, pp. 1106–1118, 2016.

[22] R. Penicka, J. Faigl, P. Vana, and M. Saska, Dubins orienteeringproblem, IEEE Robotics and Automation Letters, Vol. 2, No. 2, pp.1210–1217, 2017.

[23] G. Erdogan and G. Laporte, The orienteering problem with variableprofits, Networks, Vol. 61, No. 2 pp. 104–116, 2013.

[24] S. Pourazarm and C. G. Cassandras, Optimal routing of energy-aware vehicles in transportation networks with inhomogeneouscharging nodes, IEEE Trans. on Int. Transp. Sys., Vol. 19, No. 8,pp. 2515–2527, 2018.

[25] N. Wallace, H. Kong, A. Hill, and S. Sukkarieh, Orienteering prob-lem with replenishment, Proc. of the 16th IEEE CASE, submittedand under review, 2020.

[26] S. Kim, S. J. Guy, W. Liu, D. Wilkie, R. W. Lau, M. C. Lin, and D.Manocha, BRVO: Predicting pedestrian trajectories using velocity-space reasoning, The Int. Journal of Robotics Research, Vol. 34, No.2, pp. 201–217, 2015.

[27] C. Katrakazas, M. Quddus, W. H. Chen, and L. Deka, Real-timemotion planning methods for autonomous on-road driving: state-of-the-art and future research directions, Transp. Research Part C:Emerging Tech., Vol. 60, pp. 416–442, 2015.

[28] W. Schwarting, J. Alonso-Mora, and D. Rus, Planning and decision-making for autonomous vehicles. Annual Review of Control,Robotics, and Autonomous Systems, Vol. 1 pp. 187-210, 2018.

[29] S. S. Ge and Y. J. Cui, Dynamic motion planning for mobile robotsusing potential field method, Autonomous Robots, Vol. 13, pp. 207-222, 2002.

[30] B. Douillard, J. Underwood, N. Kuntz, V. Vlaskine, A. Quadros,P. Morton, and A. Frenkel, On the segmentation of 3d lidar pointclouds, Proc. of IEEE ICRA, pp. 2798–2805, Shanghai, China, 2011.

[31] W. Liu, D. Anguelov, D. Erhan, C. Szegedy, S. Reed, C. Y. Fu, andA. C. Berg, SSD: Single shot multibox detector, Proc. of EuropeanConf. on Computer Vision, 2016.

[32] S. Verma, J. S. Berrio, S. Worrall, and E. Nebot, Automatic extrinsiccalibration between a camera and a 3d lidar using 3d point and planecorrespondences, Proc. of IEEE Intelligent Transp. Sys. Conf., pp.3906–3912, Auckland, New Zealand, 2019.

[33] A. Hornung, K.M. Wurm, M. Bennewitz, C. Stachniss, and W. Bur-gard, OctoMap: An efficient probabilistic 3D mapping frameworkbased on Octrees, Autonomous Robots, Vol. 34, pp. 189-206, 2013.