distributionally robust sampling-based motion planning

6
Distributionally Robust Sampling-Based Motion Planning Under Uncertainty Tyler Summers Abstract—We propose a distributionally robust incremen- tal sampling-based method for kinodynamic motion planning under uncertainty, which we call distributionally robust RRT (DR-RRT). In contrast to many approaches that assume Gaus- sian distributions for uncertain parameters, here we consider moment-based ambiguity sets of distributions with given mean and covariance. Chance constraints for obstacle avoidance and internal state bounds are then enforced under the worst- case distribution in the ambiguity set, which gives a coherent assessment of constraint violation risks. The method generates risk-bounded trajectories and feedback control laws for robots operating in dynamic, cluttered, and uncertain environments, explicitly incorporating localization error, stochastic process disturbances, unpredictable obstacle motion, and uncertain obstacle location. We show that the algorithm is probabilisti- cally complete under mild assumptions. Numerical experiments illustrate the effectiveness of the algorithm. I. I NTRODUCTION With robots operating in increasingly dynamic and un- certain environments, more sophisticated motion planning and control algorithms are needed for ensuring safe and efficient autonomous behavior. Many important advances in motion planning have been made in deterministic settings [1]–[7], and recently several extensions have been developed to explicitly incorporate various types of uncertainty into motion planning and control algorithms [8]–[23]. Research on motion planning under uncertainty can be categorized according to how the uncertainty is parame- terized and the approach for searching the state space for feasible trajectories and feedback controllers. Two broad approaches to uncertainty parameterization use probabilis- tic and robust quantifications. In probabilistic approaches, uncertain quantities are modeled as random variables that have given probability distributions, and typically chance constraints are enforced so that nominal constraints hold with prescribed probability [9]–[20]. In robust approaches, only the support of the distribution is assumed to be known, and constraints are enforced for the worst-case disturbances in the support set [21], [22]. Two broad approaches to searching for feasible trajectories are sampling-based [9]–[18] and optimization-based methods [19], [20], [24], and both types have been developed to explicitly incorporate uncertainty. Other approaches handle uncertainty implicitly by designing feedback controllers based on deterministic models [23]. Although Gaussian assumptions and chance constraints are commonly made to ensure computational tractability, such assumptions are rarely justifiable based on actual data from The author is with the University of Texas at Dallas, E-mail: [email protected]. This work was sponsored by the Army Re- search Office and accomplished under Grant Number: W911NF-17-1-0058. nonlinear robotic systems. This can cause significant mis- calculations of risk, and the underlying risk metrics do not necessarily possess desirable properties such as coherence [25]. However, recent results from the emerging area of distributionally robust optimization have shown that a much more sophisticated treatment of stochastic uncertainty is possible without sacrificing computational tractability [26]– [32]. These approaches consider ambiguity sets of distri- butions based on data or estimated quantities, rather than making strong assumptions about the form of the distribution. However, to the author’s best knowledge, this framework has not been utilized within robotic motion planning and control algorithms. More sophisticated and nuanced approaches for quantifying risks can enable robots to operate successfully in increasingly complex, real-world environments. We propose a distributionally robust incremental sampling-based method for kinodynamic motion planning under uncertainty, which we call distributionally robust RRT (DR-RRT). In contrast to many approaches that assume Gaussian distributions for uncertain parameters, here we consider moment-based ambiguity sets of distributions with given mean and covariance. Chance constraints for obstacle avoidance and internal state bounds are then enforced under the worst-case distribution in the ambiguity set, which gives a coherent assessment of constraint violation risks. The method generates risk-bounded trajectories and feedback control laws for robots operating in dynamic, cluttered, and uncertain environments, explicitly incorporating localization error, stochastic process disturbances, unpredictable obstacle motion, and uncertain obstacle location. This approach may be particularly effective for nonlinear systems, where moments are only approximations of non-Gaussian distributions. We show that the algorithm is probabilistically complete under mild assumptions. Numerical experiments illustrate the effectiveness of the algorithm. The rest of the paper is organized as follows. Section II formulates the model and distributionally robust motion plan- ning problem. Section III presents our incremental sampling- based algorithm for generating distributionally robust trajec- tories and feedback control policies and provides analysis of probabilistic completeness. Section IV presents illustrative numerical experiments. Section V concludes and summarizes ongoing and future research. II. PROBLEM FORMULATION We begin by formulating a distributionally robust motion planning under uncertainty problem. The formulation fol- lows an analogous approach for chance-constrained motions planning with Gaussian distributions [11].

Upload: others

Post on 23-Apr-2022

5 views

Category:

Documents


0 download

TRANSCRIPT

Page 1: Distributionally Robust Sampling-Based Motion Planning

Distributionally Robust Sampling-Based Motion Planning Under Uncertainty

Tyler Summers

Abstract— We propose a distributionally robust incremen-tal sampling-based method for kinodynamic motion planningunder uncertainty, which we call distributionally robust RRT(DR-RRT). In contrast to many approaches that assume Gaus-sian distributions for uncertain parameters, here we considermoment-based ambiguity sets of distributions with given meanand covariance. Chance constraints for obstacle avoidance andinternal state bounds are then enforced under the worst-case distribution in the ambiguity set, which gives a coherentassessment of constraint violation risks. The method generatesrisk-bounded trajectories and feedback control laws for robotsoperating in dynamic, cluttered, and uncertain environments,explicitly incorporating localization error, stochastic processdisturbances, unpredictable obstacle motion, and uncertainobstacle location. We show that the algorithm is probabilisti-cally complete under mild assumptions. Numerical experimentsillustrate the effectiveness of the algorithm.

I. INTRODUCTION

With robots operating in increasingly dynamic and un-certain environments, more sophisticated motion planningand control algorithms are needed for ensuring safe andefficient autonomous behavior. Many important advances inmotion planning have been made in deterministic settings[1]–[7], and recently several extensions have been developedto explicitly incorporate various types of uncertainty intomotion planning and control algorithms [8]–[23].

Research on motion planning under uncertainty can becategorized according to how the uncertainty is parame-terized and the approach for searching the state space forfeasible trajectories and feedback controllers. Two broadapproaches to uncertainty parameterization use probabilis-tic and robust quantifications. In probabilistic approaches,uncertain quantities are modeled as random variables thathave given probability distributions, and typically chanceconstraints are enforced so that nominal constraints hold withprescribed probability [9]–[20]. In robust approaches, onlythe support of the distribution is assumed to be known, andconstraints are enforced for the worst-case disturbances in thesupport set [21], [22]. Two broad approaches to searchingfor feasible trajectories are sampling-based [9]–[18] andoptimization-based methods [19], [20], [24], and both typeshave been developed to explicitly incorporate uncertainty.Other approaches handle uncertainty implicitly by designingfeedback controllers based on deterministic models [23].

Although Gaussian assumptions and chance constraints arecommonly made to ensure computational tractability, suchassumptions are rarely justifiable based on actual data from

The author is with the University of Texas at Dallas, E-mail:[email protected]. This work was sponsored by the Army Re-search Office and accomplished under Grant Number: W911NF-17-1-0058.

nonlinear robotic systems. This can cause significant mis-calculations of risk, and the underlying risk metrics do notnecessarily possess desirable properties such as coherence[25]. However, recent results from the emerging area ofdistributionally robust optimization have shown that a muchmore sophisticated treatment of stochastic uncertainty ispossible without sacrificing computational tractability [26]–[32]. These approaches consider ambiguity sets of distri-butions based on data or estimated quantities, rather thanmaking strong assumptions about the form of the distribution.However, to the author’s best knowledge, this framework hasnot been utilized within robotic motion planning and controlalgorithms. More sophisticated and nuanced approaches forquantifying risks can enable robots to operate successfullyin increasingly complex, real-world environments.

We propose a distributionally robust incrementalsampling-based method for kinodynamic motion planningunder uncertainty, which we call distributionally robust RRT(DR-RRT). In contrast to many approaches that assumeGaussian distributions for uncertain parameters, here weconsider moment-based ambiguity sets of distributions withgiven mean and covariance. Chance constraints for obstacleavoidance and internal state bounds are then enforced underthe worst-case distribution in the ambiguity set, which givesa coherent assessment of constraint violation risks. Themethod generates risk-bounded trajectories and feedbackcontrol laws for robots operating in dynamic, cluttered, anduncertain environments, explicitly incorporating localizationerror, stochastic process disturbances, unpredictable obstaclemotion, and uncertain obstacle location. This approachmay be particularly effective for nonlinear systems,where moments are only approximations of non-Gaussiandistributions. We show that the algorithm is probabilisticallycomplete under mild assumptions. Numerical experimentsillustrate the effectiveness of the algorithm.

The rest of the paper is organized as follows. Section IIformulates the model and distributionally robust motion plan-ning problem. Section III presents our incremental sampling-based algorithm for generating distributionally robust trajec-tories and feedback control policies and provides analysis ofprobabilistic completeness. Section IV presents illustrativenumerical experiments. Section V concludes and summarizesongoing and future research.

II. PROBLEM FORMULATION

We begin by formulating a distributionally robust motionplanning under uncertainty problem. The formulation fol-lows an analogous approach for chance-constrained motionsplanning with Gaussian distributions [11].

Page 2: Distributionally Robust Sampling-Based Motion Planning

A. Model

The robot dynamics are modeled by the stochasticdiscrete-time linear time invariant system

xt+1 = Axt +But + wt, (1)

where xt ∈ Rn is the system state at time t, ut ∈ Rm

is the input at time t, A is the dynamics matrix, B isthe input matrix, and wt ∈ Rn is a zero-mean randomvector independent and identically distributed across time.The distribution Pw of wt is unknown (and not necessarilyGaussian) and will be assumed to belong to an ambiguityset Pw of distributions, which will be discussed in detailshortly. The initial condition x0 may be known exactly orsubject to a similar uncertainty model, with the distributionof x0 belonging to an ambiguity set, Px0 ∈ Px.

The system is nominally subject to constraints on the stateand input of the form

xt ∈ Xt = X\X1t\ · · · \Xnot, ut ∈ U , (2)

where X ,X1t, · · · ,Xnot ⊂ Rn, U ⊂ Rm are assumed to beconvex polytopes, and the operator \ denotes set subtraction.The sets X and U represent state and input constraintson the robot, and Xit represent a set of no obstacles inthe environment to be avoided. We assume the shape andorientation of obstacles to be known, but that their placementand motion is subject to uncertainty:

Xit = X 0i + cit + cit, i = 1, ..., no, (3)

where + here denotes set translation. In particular, X 0i ⊂ Rn

represents the known shape of obstacle i, cit ∈ Rn representsa known nominal translation, and cit ∈ Rn is a randomvector that represents an unknown location or unpredictableobstacle motion, with unknown distribution P cit ∈ Pcit.

Since constraint and obstacle sets are assumed polytopic,they can be represented by finite sets of linear inequalities

U = {ut | Auut ≤ bu}X = {xt | A0xt ≤ b0}, Xit = {xt | Aixt ≤ bit},

(4)

where bu ∈ Rnu , b0 ∈ RnE , bit ∈ Rni , and Au, A0,and Ai are matrices of appropriate dimension. The non-convex obstacle avoidance constraints can be expressed asthe disjunction

¬(Aixt ≤ bit), ∀i = 1, ..., no

⇔ ∨nij=1 (aTijxt ≥ aTijcijt),

(5)

where ∨ denotes disjunction and cijt = cijt + cit is a pointnominally on the jth constraint of the ith obstacle whosecovariance is the same as that of cit.

The model incorporates three distinct types of uncertainty:internal predictive and localization uncertainty from theprocess noise wt and the initial state x0, and external envi-ronmental uncertainty from the unknown obstacle locations.

B. A Distributionally Robust Motion Planning ProblemThe goal of the motion planning problem is to find a

feedback control policy π = [π0, ..., πT−1] with ut = πt(xt)that yields a feasible and minimum cost trajectory and fromthe initial state x0 to a goal set Xgoal ⊂ Rn. Accordingly,we seek to (approximately) solve the distributionally robustconstrained stochastic optimal control problem

minimizeπ∈Π

T−1∑t=0

`t(Ext,Xgoal, ut) + `T (ExT ,Xgoal)

subject to xt+1 = Axt +But + wt

x0 ∼ Px0∈ Px, wt ∼ Pw ∈ Pw

ut ∈ Uinf

Pxt∈PPxt

(xt ∈ Xt) ≥ 1− α

Xt = X\X1t\ · · · \Xnot

Xit = X 0i + cit + cit, i = 1, ..., no

cit ∼ P cit ∈ Pcit, t = 0, ..., T − 1,(6)

where P is an ambiguity set of marginal state distributionsand α ∈ (0, 0.5] is a user-prescribed risk parameter. Thestage cost functions `t(·) quantify the robot’s distance tothe goal set and actuator effort, and are assumed to beexpressed in terms of the state mean Ext, so that allstochasticity appears in the constraints. A key distinction ofthe present work is that the state constraints are expressed asdistributionally robust chance constraints. Standard chanceconstraints require the nominal state constraints xt ∈ Xtto be satisfied with probability 1 − α. In contrast, herewe enforce distributionally robust chance constraints, whichrequire the nominal state constraints xt ∈ Xt to be satisfiedwith the same probability, but under the worst case probabil-ity distribution in the ambiguity set1. In the next section, wepresent a probabilistically complete sampling-based motionplanning algorithm for generating coherent distributionallyrobust risk constrained trajectories and feedback controllaws in the presence of both internal and environmentaluncertainties.

C. Ambiguity Sets and Distributionally Robust OptimizationMost motion planning algorithm do not explicitly in-

corporate uncertainty, and even the ones that do almostalways assume a functional form (often Gaussian) for prob-ability distributions of uncertain quantities. Assumptions ofGaussianity are rarely justifiable based on actual data fromnonlinear robotic systems, but are made in the name ofcomputational tractability. However, recent results from theemerging area of distributionally robust optimization haveshown that a much more sophisticated treatment of stochasticuncertainty is possible without sacrificing computationaltractability [26]–[32].

Distributionally robust optimization approaches can becategorized based on the form of the ambiguity set. There

1It is straightforward to extend our approach to handle pathwise stateconstraints of the form infPxt∈P Pxt (∧t(xt ∈ Xt)) ≥ 1 − αp, but werestrict attention to stage wise constraints to simplify the exposition.

Page 3: Distributionally Robust Sampling-Based Motion Planning

are several different parameterizations, including those basedon moments, support, directional derivatives [26], [27], f -divergences [28], [31], and Wasserstein balls [30]. For exam-ple, a moment-based ambiguity set includes all distributionswith a fixed moments up to some order (e.g., fixed firstand second moments), and Wasserstein-based ambiguity setsinclude a ball of distributions within a given Wassersteindistance from some base distribution (such as an empiricaldistribution on a training dataset). We will focus here onmoment-based ambiguity sets, though other parameteriza-tions are interesting and relevant for robotic motion planningand will be pursued in future work.

Suppose the feedback control policy is a fixed affinefunction ut = Ktxt + kt and that the second momentsof the initial state and disturbance are denoted by Σx0

=E(x0 − x0)(x0 − x0)T and W = Ewtw

Tt and known (or

estimated based on historical data). Then the state meanxt = Ext and covariance matrix Σxt

= E(xt−xt)(xt−xt)Tevolve according to

xt+1 = (A+BKt)xt +Bkt

Σxt+1= (A+BKt)Σxt

(A+BKt)T +W.

(7)

Since the primitive distributions Px0and Pw are not assumed

to be Gaussian, then neither are the marginal state distri-butions Pxt

. In contrast to previous work with Gaussianityassumptions where the moment dynamics (7) completelycharacterize the marginals, e.g., [11], here we consider themoment-based ambiguity set

P = {Pxt| Ext = xt, E(xt − xt)(xt − xt)T = Σxt

}. (8)

Furthermore, suppose that Ecijt = cijt and E(cijt −cijt)(cijt − cijt)

T = Σcjt, which defines a correspondingmoment-based ambiguity set for obstacle motion.

Under the moment-based ambiguity set (8), a constrainton the worst-case probability of violating the jth constraintof obstacle i

supPxt∈P

Pxt(aTijxt ≥ aTijcijt) ≤ αi (9)

is equivalent (see, e.g., [26]) to the linear constraint on thestate mean xt

aTij xt ≥ aTij cijt +

√1− αiαi‖(Σt + Σcjt)aij‖2. (10)

This represents a deterministic tightening of the nominalconstraint constraint to enforce the corresponding distribu-tionally robust constraint. This tightening has the generalsame form as the one involving Gaussian distributions, butthe scaling constant

√1−αij

αijis larger than the Gaussian

one, leading to a stronger tightening that reflects the weakerassumptions about the uncertainty distributions.

Since the robot collides with the obstacle if any one ofthese constraints is violated, then supPxt∈P

Pxt(xt ∈ Xit) ≤

αi is equivalent to

∨nj

j=1

(aTij xt ≥ aTij cijt +

√1− αiαi‖(Σt + Σcjt)aij‖2

).

(11)

Similarly, a constraint on the worst-case probabil-ity of violating jth state constraint defining X , viz.supPxt∈P

Pxt(aT0jxt ≥ aT0jc0j) ≤ α0j is equivalent to

aT0j xt ≤ aT0jc0j −

√1− α0j

α0j‖Σta0j‖2, (12)

where c0j is a point on the jth state constraint.Putting all of this together gives the following result.Theorem 1: Consider a trajectory (x0,Σx0), ..., (xT ,ΣxT

)of the first and second moments of the state distributiongiven by (7). Suppose the state means satisfy the constraints(11) and (12) for each time step, each obstacle, and eachenvironmental constraint, and that the constraint satisfactionparameters are chosen such that

∑nE

i=1 α0i +∑no

i=1 αj = α.Then the trajectory satisfies the distributionally robust stateconstraints

infPxt∈P

Pxt(xt ∈ Xt) ≥ 1− α (13)

Proof: The distributionally robust state constraint (13)can equivalently be written in terms of a probabilistic upperbound on constraint violation: supPxt∈P

Pxt(xt /∈ Xt) ≤ α.

Since the constraint sets are polytopic, Boole’s inequalityand (11) and (12) can be used to obtain the bound

supPxt∈P

Pxt(xt /∈ Xt)

≤ supPxt∈P

Pxt(xt /∈ X ) +

no∑i=1

supPxt∈P

Pxt(xt ∈ Xit)

≤nE∑j=1

supPxt∈P

Pxt(aT0jxt ≥ aT0jc0j) +

no∑i=1

supPxt∈P

Pxt(xt ∈ Xit)

≤nE∑i=1

α0i +

no∑i=1

αj = α.

In the next section, we will present a sampling-basedmotion planning algorithm that incrementally generates statetrajectories and feedback control laws that satisfy the dis-tributionally robust constraints. It is possible to reduce con-servatism associated with applying Boole’s inequality by ex-ploiting the trajectory-wise incremental constraint checkingof sampling-based motion planning algorithms to dynami-cally allocate risk amongst the various constraints as in [11];this will be pursued in future work.

III. DISTRIBUTIONALLY ROBUST RRT (DR-RRT)

This section describes Distributionally Robust RRT, anincremental sampling-based method for kinodynamic motionplanning under uncertainty. The algorithm grow trees of statedistributions, rather than trees of states, and incorporatesdistributionally robust probabilistic constraints to certify fea-sibility of nominal state mean trajectories.

A. Algorithm

Tree Expansion. Pseudocode for distributionally robustRRT tree expansion is shown in Algorithm 1. In the firststep, a random sample is taken from the feasible state set.

Page 4: Distributionally Robust Sampling-Based Motion Planning

Algorithm 1 DR-RRT: Tree ExpansionInputs: current tree T and timestep txs = sample(Xt)(xnearest,Σnearest) = nearestMnodes(xs, T )for i ∈ {1, ...,M} do

(xtraj ,Σtraj) = steer(xnearest,Σnearest, xs)while DRCollisionCheck(xtraj ,Σtraj) doT .AddNodes(xtraj ,Σtraj)T .AddEdges(xnearest, xtraj)

Then a set of M ≥ 1 tree nodes nearest to the sampleare selected according to some appropriate distance metricand returned in ascending order. It is typically advantageousto use a dynamic control-based distance metric, such as anoptimal cost-to-go function, instead of a purely geometricdistance, in order to efficiently explore the reachable set ofthe dynamics and increase likelihood of generating collision-free trajectories [6]. Attempts are then made to steer therobot from the nearest tree nodes to the random sample.For this step, we use an unconstrained optimal feedbackcontrol policy obtained via a finite horizon linear quadraticdynamic programming algorithm. This policy is then usedto propagate the state mean and covariance matrix, and theentire trajectory is returned by the steer function. However,many different control design methods may be used; in futurework we will explore more sophisticated steering methodsthat also explicitly incorporate some of the nearby obstacleconstraints. Each state distribution in the trajectory is thenchecked for distributionally robust probabilistic constraintsatisfaction, and feasible portions of the trajectory are addedto the tree. This expansion is then repeated until a nodefrom the goal set is added to the tree. At that point, adistributionally robust feasible trajectory is obtained from thetree root to the goal set.

Dynamic execution. For dynamic and stochastic environ-ments, the tree expansion can be updated dynamically as therobot moves and new information about the environment isobtained. The minimum cost feasible path currently availablein the tree can be executed, and then new tree branches canbe grown from the new state estimate and infeasible branchescan be pruned.

B. Analysis

Assumption 1: We assume the following:

(i) There exists a sequence of feasible control inputsu0, ..., uT−1 (possibly generated by a control policyπ = [π0, ..., πT−1] with ut = πt(xt)) such that allconstraints in (6) are satisfied by the state distributiontrajectory (x0,Σx0

), ..., (xT ,ΣxT) obtained via (7).

(ii) Each node added during tree expansion is separatedfrom its parent node by a distance of at least ε > 0.

(iii) When attempting to connect a random sample from thefeasible set to the tree by the steering function, inputsare randomly selected from a finite set, which containsall inputs in the feasible sequence from (i).

In practice, inputs are not chosen randomly as in (iii), andthe exploration will be most effective when advanced controlmethods are used to steer the robot toward random samples.We have the following result, which follows along the linesof the analogous result for chance constrained RRT in [11].

Theorem 2: Under Assumption 1, the proposed distribu-tionally robust RRT algorithm (DR-RRT) in Algorithm 1 isprobabilistically complete, i.e., it returns a feasible solutionwith probability approaching 1 as the number of samplestends to infinity.

Proof: By induction. Suppose that the tree contains thefeasible state distribution (xt,Σxt) generated by applying thefeasible control input sequence u0, ..., ut−1 from Assumption1(i). Since all tree nodes have a non-empty Voronoi regiondue to Assumption 1(ii), there is a strictly positive probabilitythat the node corresponding to (xt,Σxt

) will be selected forexpansion. By Assumption 1(iii) there is a strictly positiveprobability that the steering input ut is selected and resultsin the feasible state distribution (xt+1,Σxt+1

) being addedto the tree and connected to (xt,Σxt

). Thus, as the numberof samples tends to infinity, the probability of generating thefeasible sequence approaches 1. Basing the tree at the initialnode (x0,Σx0) completes the proof by induction.

C. Variations

Here we list several variations of the basic DR-RRTalgorithm that are being pursued in future research, someof which are straightforward to implement.

Asymptotic Optimality. It is known that the standardRRT algorithm is not asymptotically optimal, i.e., the feasiblesolution will not in general minimize the cost function as thenumber of samples tends to infinity. The recently proposedRRT* algorithm achieves asymptotic optimality by rewiringthe tree for lower cost paths around a set of nodes near thesample [7]. A similar approach can be taken here to obtaina distributionally robust RRT* algorithm (DR-RRT*) that isboth probabilistically complete and asymptotically optimal.

Nonlinear Dynamics. The DR-RRT algorithm can be ap-plied to systems with nonlinear dynamics by linearizing thesystem and propagating first and second order moments. Inthis case, the distributionally robust framework is particularlycompelling, since the first and second moments are onlyapproximations of the true state distribution, even when theprimitive distributions are Gaussian.

Higher Order Moment Propagation. Higher order mo-ments beyond first and second order can be propagated,in order to sharpen risk estimates. This can be especiallyeffective for nonlinear systems. For example, third and fourthorder moments can capture skewness and heaviness of tailsand lead to far less conservative trajectories than thoseobtained by only using first and second moments.

Output feedback with recursive filtering. In manyrobotic systems, the state must be estimated based on noisysensor data. A state estimator can be used to propagate ajoint distribution of the true state and state estimate basedon the dynamic model and sensor data. For example, theKalman filter and its many variations can be used, and the

Page 5: Distributionally Robust Sampling-Based Motion Planning

distributionally robust approach may be an effective way tohandle risks associated with state estimation, particularly forextended Kalman filters for nonlinear systems.

Alternative ambiguity sets. As mentioned previously,other DR-RRT variations can be obtained using differentparameterizations of the ambiguity set. For example, Wasser-stein balls centered on empirical data-based distributionsoffer a natural way to incorporate knowledge about distribu-tions that come from observed finite training datasets. Suchan approach may be effective for particle simulations andparticle filters of nonlinear systems. Furthermore, a combi-nation of moment- and data-based distribution parameteriza-tions could be used to combine their relative advantages.

IV. NUMERICAL EXPERIMENTS

We now present numerical experiments to illustrate theproposed distributionally robust RRT algorithm (DR-RRT).

A. Double Integrator in Cluttered Environment

We consider a unit mass robot with discrete-time stochas-tic double integrator dynamics moving in a bounded andcluttered two-dimensional environment [0, 1]2. The systemdynamics matrices are

A =

1 0 dt 00 1 0 dt0 0 1 00 0 0 1

, B =

dt2

20

0 dt2

2dt 00 dt

, (14)

where dt = 0.1s and the states are the two dimensionalposition and velocity with two dimensional force inputs. Theinitial position is [0.5, 0], the initial velocity is zero, and theinitial state and disturbance covariance matrices are

Σ0 = 10−3

1 0 0 00 1 0 00 0 0 00 0 0 0

, W = 10−3

0 0 0 00 0 0 00 0 2 10 0 1 2

.

(15)The environment contains randomly located and sized rect-

angular obstacles, which are static and treated by the robot asdeterministic, so that all uncertainty in this example comesfrom the unknown initial state and process disturbance. Therobot is treated as a point mass (without loss of generality,since a known geometry can be easily handled by a fixedtightening of the state constraints), and the environmentalboundaries are not treated probabilistically.

To steer the robot from a tree node state xt to a randomfeasible sample xs, we solve a discrete time linear quadraticoptimal control problem to compute the affine state feedbackpolicy that minimizes the cost function

E

T−1∑t=0

(xt−xs)TQ(xt−xs)+uTt Rut+(xT−xs)TQ(xT−xs)

(16)

with T = 10, Q =

[40I 00 0.1I

], and R = 0.2I . The

distributionally robust state constraints are enforced withprobabilistic satisfaction parameter α = 0.1. The quadraticoptimal cost-to-go function is also used as the distance metricto select tree nodes closest to the sample.

0 0.2 0.4 0.6 0.8 10

0.2

0.4

0.6

0.8

1

Fig. 1. Illustration of Distributionally Robust RRT (DR-RRT) for thestochastic double integrator robot. The thick lines represent trajectoriesdistributionally robust trajectories of the state mean xt, and the ellipsesshow one standard deviation uncertainty regions of the state position derivedfrom the position block of the covariance matrix Σt at sampled positions.The DR-RRT algorithm generates more conservative trajectories around theobstacles, explicitly incorporating the uncertainty in the state due to theinitial localization and system dynamics uncertainties.

0 0.2 0.4 0.6 0.8 10

0.2

0.4

0.6

0.8

1

Fig. 2. RRT for the stochastic double integrator robot without the distri-butionally robust constraint tighetening. Since uncertainty is not explicitlyincorporated into collision checking, trajectories with high risk of collisionare generated.

B. Results and Discussion

Figures 1 and 2 show RRTs with and without the distri-butionally robust constraint tightening, respectively. It canbe easily seen that the DR-RRT generates more conservativetrajectories around the obstacles, explicitly incorporating theuncertainty in the state due to the initial localization andsystem dynamics uncertainties. Due to the use of closed-loop feedback control policies in the steering function, thesize of the uncertainty ellipses remains bounded as the treeis constructed. The feasible set remains effectively exploredwith DR-RRT, although certain regions may be deemed torisky to reach, such as the top left corner that can onlybe reached through narrow gaps between obstacles and theenvironment boundary. The algorithm can also be used forhigher order dynamics and state distributions propagatedfrom linearized dynamics of nonlinear systems. Computationtimes are the same as chance-constrained RRT [11], since the

Page 6: Distributionally Robust Sampling-Based Motion Planning

problems have the same form.The sizes of the uncertainty ellipses depend strongly

on the steering control method. In the current algorithm,the probabilistic constraint checking is decoupled from thesteering control design; the robot is steered from the treetoward random samples, and then the trajectory is checkfor probabilistic feasibility. Much more effective explorationof the space and generation of collision free trajectoriescould be obtained by coupling the local trajectory generationand control design with the constraints. For example, affinedisturbance feedback with stochastic model predictive con-trol could compute steering feedback policies that explicitlyaccount for a subset of nearby obstacle constraints [33]. Thiswill be pursued in future work.

V. CONCLUSIONS

We have proposed a distributionally robust incrementalsampling-based algorithm for kinodynamic motion planningunder uncertainty, DR-RRT. It effectively generates risk-bounded trajectories for robots operating in uncertain and dy-namic environments. The distributionally robust frameworkfor explicitly incorporating stochastic uncertainty handlesrisk in a more sophisticated way then state-of-the-art methodsby considering a (moment-based) ambiguity set of distribu-tions for uncertain parameters, rather than making strongassumptions about the specific form of the distributions.The algorithm is shown to be probabilistically completeunder mild assumptions. Numerical experiments illustrate theeffectiveness of the algorithm.

In ongoing and future work, we are exploring several vari-ations mentioned above, including an asymptotically optimalversion DR-RRT*, distribution propagation for nonlinearsystems and with higher order moments, output feedbackwith recursive filtering to incorporate sensing uncertainty,and alternative ambiguity sets, and more sophisticated steer-ing laws that couple feedback steering controller design withprobabilistic collisions obstacle avoidance more tightly.

REFERENCES

[1] J.-C. Latombe, Robot motion planning. Springer, 2012, vol. 124.[2] S. M. LaValle, Planning algorithms. Cambridge Univ. Press, 2006.[3] J. J. Kuffner and S. M. LaValle, “RRT-connect: An efficient approach

to single-query path planning,” in IEEE International Conference onRobotics and Automation, vol. 2. IEEE, 2000, pp. 995–1001.

[4] L. E. Kavraki, P. Svestka, J.-C. Latombe, and M. H. Overmars, “Prob-abilistic roadmaps for path planning in high-dimensional configurationspaces,” IEEE Transactions on Robotics and Automation, vol. 12,no. 4, pp. 566–580, 1996.

[5] S. LaValle and J. Kuffner, “Randomized kinodynamic planning,”International Journal of Robotics Research, vol. 20, no. 5, pp. 378–400, 2001.

[6] E. Frazzoli, M. A. Dahleh, and E. Feron, “Real-time motion planningfor agile autonomous vehicles,” AIAA Journal of Guidance, Control,and Dynamics, vol. 25, no. 1, pp. 116–129, 2002.

[7] S. Karaman and E. Frazzoli, “Sampling-based algorithms for optimalmotion planning,” The International Journal of Robotics Research,vol. 30, no. 7, pp. 846–894, 2011.

[8] S. M. LaValle and R. Sharma, “On motion planning in changing, par-tially predictable environments,” The International Journal of RoboticsResearch, vol. 16, no. 6, pp. 775–805, 1997.

[9] N. A. Melchior and R. Simmons, “Particle RRT for path planningwith uncertainty,” in IEEE International Conference on Robotics andAutomation, 2007, pp. 1617–1624.

[10] S. C. Ong, S. W. Png, D. Hsu, and W. S. Lee, “Planning under uncer-tainty for robotic tasks with mixed observability,” The InternationalJournal of Robotics Research, vol. 29, no. 8, pp. 1053–1068, 2010.

[11] B. Luders, M. Kothari, and J. How, “Chance constrained RRT for prob-abilistic robustness to environmental uncertainty,” in AIAA Guidance,Navigation, and Control Conference, 2010, p. 8160.

[12] A. Bry and N. Roy, “Rapidly-exploring random belief trees for motionplanning under uncertainty,” in IEEE International Conference onRobotics and Automation, 2011, pp. 723–730.

[13] B. Luders and J. How, “Probabilistic feasibility for nonlinear systemswith non-gaussian uncertainty using RRT,” in InfotechAerospace 2011.

[14] J. Van Den Berg, P. Abbeel, and K. Goldberg, “LQG-MP: Optimizedpath planning for robots with motion uncertainty and imperfect stateinformation,” The International Journal of Robotics Research, vol. 30,no. 7, pp. 895–913, 2011.

[15] J. Van Den Berg, S. Patil, and R. Alterovitz, “Motion planningunder uncertainty using iterative local optimization in belief space,”International Journal of Robotics Research, vol. 31, no. 11, pp. 1263–78, 2012.

[16] N. E. Du Toit and J. W. Burdick, “Robot motion planning in dynamic,uncertain environments,” IEEE Transactions on Robotics, vol. 28,no. 1, pp. 101–115, 2012.

[17] G. S. Aoude, B. D. Luders, J. M. Joseph, N. Roy, and J. P. How,“Probabilistically safe motion planning to avoid dynamic obstacleswith uncertain motion patterns,” Autonomous Robots, vol. 35, no. 1,pp. 51–76, 2013.

[18] A.-A. Agha-Mohammadi, S. Chakravorty, and N. M. Amato, “Firm:Sampling-based feedback motion-planning under motion uncertaintyand imperfect measurements,” The International Journal of RoboticsResearch, vol. 33, no. 2, pp. 268–304, 2014.

[19] L. Blackmore, M. Ono, A. Bektassov, and B. C. Williams, “A proba-bilistic particle-control approximation of chance-constrained stochasticpredictive control,” IEEE Transactions on Robotics, vol. 26, no. 3, pp.502–517, 2010.

[20] L. Blackmore, M. Ono, and B. C. Williams, “Chance-constrainedoptimal path planning with obstacles,” IEEE Transactions on Robotics,vol. 27, no. 6, pp. 1080–1094, 2011.

[21] B. D. Luders, S. Karaman, and J. P. How, “Robust sampling-basedmotion planning with asymptotic optimality guarantees,” in AIAAGuidance, Navigation, and Control (GNC) Conference, 2013, p. 5097.

[22] J. Ding, E. Li, H. Huang, and C. J. Tomlin, “Reachability-basedsynthesis of feedback policies for motion planning under bounded dis-turbances,” in International Conference on Robotics and Automation.IEEE, 2011, pp. 2160–2165.

[23] R. Tedrake, I. Manchester, M. Tobenkin, and J. Roberts, “LQR-trees: Feedback motion planning via sums-of-squares verification,”International Journal of Robotics Research, vol. 29, no. 8, pp. 1038–52, 2010.

[24] A. Jasour and C. Lagoa, “Convex relaxations of a probabilisticallyrobust control design problem,” in IEEE Conference on Decision andControl. IEEE, 2013, pp. 1892–97.

[25] R. T. Rockafellar, “Coherent approaches to risk in optimization underuncertainty,” Tutorials in operations research, vol. 3, pp. 38–61, 2007.

[26] G. C. Calafiore and L. El Ghaoui, “On distributionally robust chance-constrained linear programs,” Journal of Optimization Theory andApplications, vol. 130, no. 1, pp. 1–22, 2006.

[27] J. Goh and M. Sim, “Distributionally robust optimization and itstractable approximations,” Operations research, vol. 58, no. 4-part-1,pp. 902–917, 2010.

[28] Z. Hu and L. Hong, “Kullback-leibler divergence constrained distribu-tionally robust optimization,” Available: Optimization Online, 2013.

[29] W. Wiesemann, D. Kuhn, and M. Sim, “Distributionally robust convexoptimization,” Operations Research, vol. 62, no. 6, pp. 1358–76, 2014.

[30] P. M. Esfahani and D. Kuhn, “Data-driven distributionally robustoptimization using the wasserstein metric: Performance guarantees andtractable reformulations,” Math. Programming, pp. 1–52, 2015.

[31] H. Namkoong and J. C. Duchi, “Stochastic gradient methods fordistributionally robust optimization with f-divergences,” in Advancesin Neural Information Processing Systems, 2016, pp. 2208–2216.

[32] B. P. Van Parys, P. J. Goulart, and M. Morari, “Distributionally robustexpectation inequalities for structured distributions,” MathematicalProgramming, pp. 1–30, 2017.

[33] P. J. Goulart, E. C. Kerrigan, and J. M. Maciejowski, “Optimizationover state feedback policies for robust control with constraints,”Automatica, vol. 42, no. 4, pp. 523–533, 2006.