ABC-LMPC: Safe Sample-Based Learning MPC for Stochastic Nonlinear Dynamical Systems with Adjustable Boundary Conditions

Brijen Thananjeyan, Ashwin Balakrishna, Ugo Rosolia, Joseph E. Gonzalez, Aaron Ames, and Ken Goldberg

Abstract

Sample-based learning model predictive control (LMPC) strategies have recently attracted attention due to their desirable theoretical properties and good empirical performance on robotic tasks. However, prior analysis of LMPC controllers for stochastic systems has mainly focused on linear systems in the iterative learning control setting. We present a novel LMPC algorithm, Adjustable Boundary Condition LMPC (ABC-LMPC), which enables rapid adaptation to novel start and goal configurations and theoretically show that the resulting controller guarantees iterative improvement in expectation for stochastic nonlinear systems. We present results with a practical instantiation of this algorithm and experimentally demonstrate that the resulting controller adapts to a variety of initial and terminal conditions on 3 stochastic continuous control tasks.


Inferring Obstacles and Path Validity from Visibility-Constrained Demonstrations

Craig Knuth, Glen Chou, Necmiye Ozay and Dmitry Berenson

Abstract

Many methods in learning from demonstration assume that the demonstrator has knowledge of the full environment. However, in many scenarios, a demonstrator only sees part of the environment and they continuously replan as they gather information. To plan new paths or to reconstruct the environment, we must consider the visibility constraints and replanning process of the demonstrator, which, to our knowledge, has not been done in previous work. We consider the problem of inferring obstacle configurations in a 2D environment from demonstrated paths for a point robot that is capable of seeing in any direction but not through obstacles. Given a set of survey points, which describe where the demonstrator obtains new information, and a candidate path, we construct a Constraint Satisfaction Problem (CSP) on a cell decomposition of the environment. We parameterize a set of obstacles corresponding to an assignment from the CSP and sample from the set to find valid environments. We show that there is a probabilistically-complete, yet not entirely tractable, algorithm that can guarantee novel paths in the space are unsafe or possibly safe. We also present an incomplete, but empirically-successful, heuristic-guided algorithm that we apply in our experiments to 1) planning novel paths and 2) recovering a probabilistic representation of the environment.


Space-Aware Reconfiguration

Dan Halperin, Marc van Kreveld, Golan Miglioli-Levy and Micha Sharir

Abstract

We consider the problem of reconfiguring a set of physical objects into a desired target configuration, a typical (sub)task in robotics and automation, arising in product assembly, packaging, stocking store shelves, and more. In this paper we address a variant, which we call space-aware reconfiguration, where the goal is to minimize the physical space needed for the reconfiguration, while obeying constraints on the allowable collision-free motions of the objects. Since for given start and target configurations, reconfiguration may be impossible, we translate the entire target configuration rigidly into a location that admits a valid sequence of moves, where each object moves in turn just once, along a straight line, from its starting to its target location, so that the physical space required by the start and the translated target configurations is minimized.

We investigate two variants of space-aware reconfiguration for the often examined setting of n unit discs in the plane, depending on whether the discs are distinguishable (labeled) or indistinguishable (unlabeled). For the labeled case, we compute, in O(n6) time, a shortest valid translation, or one that minimizes the enclosing disc or axis-aligned rectangle of both the start and target configurations. For the significantly harder unlabeled case, we show that for almost every direction, there exists a translation in this direction that makes the problem feasible. We use this to devise heuristic solutions, where we optimize the translation under stricter notions of feasibility. We present an implementation of such a heuristic, which solves unlabeled instances with hundreds of discs in seconds.


Evasive Navigation of an Autonomous Mobile Robot in Hostile Unknown Environments

Yaron Veksler and Elon D. Rimon

Abstract

This paper considers on-line navigation of an autonomous mobile robot in an unknown hostile environment. The hostility of the environment is modeled as the requirement that the robot avoids traveling through open areas where it can be easily noticed. To move evasively through the unknown environment, the robot is allowed to move along obstacle boundary segments and locally shortest lines connecting obstacles in exposed areas of the environment. An evasive motion graph consisting of these path segments is used to compute the optimal off-line navigation path. Based on the optimal off-line path, an evasive on-line navigation algorithm called E-Nav is described. The E-Nav algorithm constructs a partial evasive motion graph in the currently known environment measured by the robot during navigation to the target. The competitive performance of the E-Nav algorithm is shown to be log-quadratic in the optimal off-line evasive path length. The E-Nav algorithm is demonstrated with a step-by-step execution example.


Neural Collision Clearance Estimator for Batched Motion Planning

J. Chase Kew, Brian Ichter, Maryam Bandari, Tsang-Wei Edward Lee and Aleksandra Faust

Abstract

We present a neural network collision checking heuristic, ClearanceNet, and a planning algorithm, CN-RRT. ClearanceNet learns to predict separation distance (minimum distance between robot and workspace) with respect to a workspace. CN-RRT then efficiently computes a motion plan by leveraging three key features of ClearanceNet. First, CN-RRT explores the space by expanding multiple nodes at the same time, processing batches of thousands of collision checks. Second, CN-RRT adaptively relaxes its clearance requirements for more difficult problems. Third, to repair errors, CN-RRT shifts its nodes in the direction of ClearanceNet’s gradient and repairs any residual errors with a traditional RRT, thus maintaining theoretical probabilistic completeness guarantees. In configuration spaces with up to 30 degrees of freedom, ClearanceNet achieves 845x speedup over traditional collision detection methods, while CN-RRT accelerates motion planning by up to 51% over a baseline and finds paths up to 36% more efficient. Experiments on an 11 degree of freedom robot in a cluttered environment confirm the method’s feasibility on real robots.


Cover Combinatorial Filters and their Minimization Problem

Yulin Zhang and Dylan A. Shell

Abstract

Recent research has examined algorithms to minimize robots’ resource footprints. The class of combinatorial filters (discrete variants of widely-used probabilistic estimators) has been studied and methods for reducing their space requirements introduced. This paper extends existing combinatorial filters by introducing a natural generalization: cover combinatorial filters. In addressing the new—but still NP-complete—problem of minimization of cover filters, we show that multiple concepts previously believed about combinatorial filters (and actually conjectured, claimed, or assumed to be) are in fact false. For instance, minimization does not induce an equivalence relation. We give an exact algorithm for the cover filter minimization problem. Unlike prior work (based on graph coloring) we consider a type of clique-cover problem, involving a new conditional constraint, from which we can find more general relations. In addition to solving the more general problem, the algorithm also corrects flaws present in all prior filter reduction methods. In employing SAT, the algorithm provides a promising basis for future practical development.


Approximation Algorithms for Multi-Robot Patrol-Scheduling with Min-Max Latency

Peyman Afshani, Mark de Berg, Kevin Buchin, Jie Gao, Maarten Löffler, Amir Nayyeri, Benjamin Raichel, Rik Sarkar, Haotian Wang and Hao-Tsung Yang

Abstract

We consider the problem of finding patrol schedules for k robots to visit a given set of n sites in a metric space. Each robot has the same maximum speed and the goal is to minimize the weighted maximum latency of any site, where the latency of a site is defined as the maximum time duration between consecutive visits of that site. The problem is NP-hard, as it has the traveling salesman problem as a special case (when k = 1 and all sites have the same weight). We present a polynomial-time algorithm with an approximation factor of O(k2log(wmax/wmin) to the optimal solution, where wmax and wmin are the maximum and minimum weight of the sites respectively. Further, we consider the special case where the sites are in 1D. When all sites have the same weight, we present a polynomial-time algorithm to solve the problem exactly. If the sites may have different weights, we present a 12-approximate solution, which runs in polynomial time when the number of robots, k, is a constant.


Locally-Connected Interrelated Network: A Forward Propagation Primitive

Nicholas Collins and Hanna Kurniawati

Abstract

End-to-end learning for planning is a promising approach for finding good robot strategies in situations where the state transition, observation, and reward functions are initially unknown. Many neural network architectures for this approach have shown positive results. Across these networks, seemingly small components have been used repeatedly in different architectures, which means improving the efficiency of these components has great potential to improve the overall performance of the network. This paper aims to improve one such component: The forward propagation module. In particular, we propose Locally-Connected Interrelated Network (LCI-Net) —a novel type of locally connected layer with unshared but interrelated weight— to improve the efficiency of information propagation and learning stochastic transition models for planning. LCI-Net is a small differentiable neural network module that can be plugged into various existing architectures. For evaluation purposes, we apply LCI-Net to QMDP-Net; QMDP-Net is a neural network for solving POMDP problems whose transition, observation, and reward functions are learned. Simulation tests on benchmark problems involving 2D and 3D navigation and grasping indicate promising results: Changing only the forward propagation module alone with LCI-Net improves QMDP-Net generalization capability by a factor of up to 10.


Optimized Synthesis of Snapping Fixtures

Tom Tsabar, Efi Fogel and Dan Halperin

Abstract

Fixtures for constraining the movement of parts have been extensively investigated in robotics, since they are essential for using robots in automated manufacturing. This paper deals with the design and optimized synthesis of a special type of fixtures, which we call snapping fixtures. Given a polyhedral workpiece P with n vertices and of constant genus, which we need to hold, a snapping fixture is a semi-rigid polyhedron G, made of a palm and several fingers, such that when P and G are well separated, we can push P toward G, slightly bending the fingers of G on the way (exploiting its mild flexibility), and obtain a configuration, where G is back in its original shape and P and G are inseparable as rigid bodies. We prove the minimal closure conditions under which such fixtures can hold parts, using Helly’s theorem. We then introduce an algorithm running in O(n3) time that produces a snapping fixture, minimizing the number of fingers and optimizing additional objectives, if a snapping fixture exists. We also provide an efficient and robust implementation of a simpler version of the algorithm, which produces the fixture model to be 3D printed and runs in O(n4) time. We describe two applications with different optimization criteria: Fixtures to hold add-ons for drones, where we aim to make the fixture as lightweight as possible, and small-scale fixtures to hold precious stones in jewelry, where we aim to maximize the exposure of the stones, namely minimize the obscuring of the workpiece by the fixture.


Sampling-based Motion Planning for Uncertain High-dimensional Systems via Adaptive Control

Christos K. Verginis, Dimos V. Dimarogonas and Lydia E. Kavraki

Abstract

This paper considers the problem of safe motion planning for high-dimensional holonomic robots with 2nd-order uncertain dynamics. We integrate sampling-based motion planning techniques with traditional adaptive feedback control and address difficulties encountered in planning for such systems. More specifically, we develop a feedback control scheme that tracks a given reference trajectory within certain bounds, while simultaneously compensating for potential uncertainty in the dynamic parameters of the robot (masses, moments of inertia) and external disturbances. Employing this result, we are able to cast the problem of kinodynamic motion planning to a geometric one, which can be usually solved more efficiently since it does not take into account the robot dynamics (a.k.a. differential constraints). Intuitively, we use a geometric planner to obtain a high-level safe path for the robot, and a low-level adaptive feedback control algorithm to execute it while taking into account the robot dynamics. Simulation results validate the proposed approach.


Every Action-Based Sensor

Grace McFassel and Dylan A. Shell

Abstract

In studying robots and planning problems, a basic question is what is the minimal information a robot must obtain to guarantee task completion. Erdmann’s theory of action-based sensors is a classical approach to characterizing fundamental information requirements. That approach uses a plan to derive a type of virtual sensor which prescribes actions that make progress toward a goal. We show that the established theory is incomplete: the previous method for obtaining such sensors, using backchained plans, overlooks some sensors. Furthermore, there are plans, that are guaranteed to achieve goals, where the existing methods are unable to provide any action-based sensor. We identify the underlying feature common to all such plans. Then, we show how to produce action-based sensors even for plans where the existing treatment is inadequate, although for these cases they have no single canonical sensor. Consequently, the approach is generalized to produce sets of sensors. Finally, we show also that this is a complete characterization of action-based sensors for planning problems and discuss how an action-based sensor translates into the traditional conception of a sensor.


Linear-Time Variational Integrators in Maximal Coordinates

Jan Brüdigam and Zachary Manchester

Abstract

Most dynamic simulation tools parameterize the configuration of multi-body robotic systems using minimal coordinates, also called generalized or joint coordinates. However, maximal-coordinate approaches have several advantages over minimal-coordinate parameterizations, including native handling of closed kinematic loops and nonholonomic constraints. This paper describes a linear-time variational integrator that is formulated in maximal coordinates. Due to its variational formulation, the algorithm does not suffer from constraint drift and has favorable energy and momentum conservation properties. A sparse matrix factorization technique allows the dynamics of a loop-free articulated mechanism with n links to be computed in O(n) (linear) time. Additional constraints that introduce loops can also be handled by the algorithm without incurring much computational overhead. Experimental results show that our approach offers speed competitive with state-of-the-art minimal-coordinate algorithms while outperforming them in several scenarios, especially when dealing with closed loops and configuration singularities.


Information Requirements of Collision-Based Micromanipulation

Alexandra Q. Nilles, Ana Pervan, Thomas A. Berrueta, Todd D. Murphey and Steven M. LaValle

Abstract

We present a task-centered formal analysis of the relative power of several robot designs, inspired by the unique properties and constraints of micro-scale robotic systems. Our task of interest is object manipulation because it is a fundamental prerequisite for more complex applications such as micro-scale assembly or cell manipulation. Motivated by the difficulty in observing and controlling agents at the micro-scale, we focus on the design of boundary interactions: the robot’s motion strategy when it collides with objects or the environment boundary, otherwise known as a bounce rule. We present minimal conditions on the sensing, memory, and actuation requirements of periodic “bouncing” robot trajectories that move an object in a desired direction through the incidental forces arising from robot-object collisions. Using an information space framework and a hierarchical controller, we compare several robot designs, emphasizing the information requirements of goal completion under different initial conditions, as well as what is required to recognize irreparable task failure. Finally, we present a physically-motivated model of boundary interactions, and analyze the robustness and dynamical properties of resulting trajectories.


Characterizing Marginalization and Incremental Operations on the Bayes Tree

Dehann Fourie, Antonio Teràn Espinoza, Michael Kaess and John Leonard

Abstract

Perception systems for autonomy are most useful if they can operate within limited/predictable computing resources. Existing algorithms in robot navigation—e.g. simultaneous localization and mapping—employ concepts from filtering, fixed-lag, or incremental smoothing to find feasible inference solutions. Using factor graphs as probabilistic modeling language, we emphasize the importance of marginalization operations on the equivalent Bayes (junction) tree. The objective is to elucidate the connection between simple tree-based message passing rules with the aforementioned state estimation approaches, and their frequently overlooked relation to direct marginalization on the Bayes tree. We characterize the inherent marginalization operation as part of the fundamental Chapman-Kolmogorov transit integrals which unifies many state-of-the-art approaches. The belief propagation model is then used to define five major tree inference strategies, with regard to computation recycling and resource constrained operation. A series of illustrative examples and results show the versatility of the method.


Synchronized Multi-Arm Rearrangement Guided by Mode Graphs with Capacity Constraints

Rahul Shome and Kostas E. Bekris

Abstract

Solving task planning problems involving multiple objects and multiple robotic arms poses scalability challenges. Such problems involve not only coordinating multiple high-DoF arms, but also searching through possible sequences of actions including object placements, and handoffs. The current work identifies a useful connection between multi-arm rearrangement and recent results in multi-body path planning on graphs with vertex capacity constraints. Solving a synchronized multi-arm rearrangement at a high-level involves reasoning over a modal graph, where nodes correspond to stable object placements and object transfer states by the arms. Edges of this graph correspond to pick, placement and handoff operations. The objects can be viewed as pebbles moving over this graph, which has capacity constraints. For instance, each arm can carry a single object but placement locations can accumulate many objects. Efficient integer linear programming-based solvers have been proposed for the corresponding pebble problem. The current work proposes a heuristic to guide the task planning process for synchronized multi-arm rearrangement. Results indicate good scalability to multiple arms and objects, and an algorithm that can find high-quality solutions fast and exhibiting desirable anytime behavior.


Hierarchical Multiobjective Shortest Path Problems

Konstantin Slutsky, Dmitry Yershov, Tichakorn Wongpiromsarn and Emilio Frazzoli

Abstract

We consider the shortest path problem on graphs with weights taking values in Cartesian products of cost monoids. Such cost structures appear in multiobjective planning including, for instance, the minimum-violation planning framework. It is known that these products often do not satisfy the conditions of a cost monoid. Classical dynamic programming graph search algorithms may therefore fail to find an optimal solution.

We isolate the concept of a regular cost monoid and propose an iterative search algorithm that finds an optimal path in graphs weighted by products of such costs. Our algorithm allows this class of multiobjective planning problems to be solved in polynomial time.


Planning to Chronicle

Hazhar Rahmani, Dylan A. Shell and Jason M. O’Kane

Abstract

An important class of applications entails a robot monitoring, scrutinizing, or recording the evolution of an uncertain time-extended process. This sort of situation leads to an interesting family of planning problems in which the robot is limited in what it sees and must, thus, choose what to pay attention to. The distinguishing characteristic of this setting is that the robot has influence over what it captures via its sensors, but exercises no causal authority over the evolving process. As such, the robot’s objective is to observe the underlying process and to produce a ‘chronicle’ of occurrent events, subject to a goal specification of the sorts of event sequences that may be of interest. This paper examines variants of such problems when the robot aims to collect sets of observations to meet a rich specification of their sequential structure. We study this class of problems by modeling a stochastic process via a variant of a hidden Markov model, and specify the event sequences of interest as a regular language, developing a vocabulary of ‘mutators’ that enable sophisticated requirements to be expressed. Under different suppositions about the information gleaned about the event model, we formulate and solve different planning problems. The core underlying idea is the construction of a product between the event model and a specification automaton. The paper reports and compares performance metrics by drawing on some small case studies analyzed in depth in simulation.


Deadlock Analysis and Resolution for Multi-Robot Systems

Jaskaran Singh Grover, Changliu Liu and Katia Sycara

Abstract

Collision avoidance for multirobot systems is a well studied problem. Recently, control barrier functions (CBFs) have been proposed for synthesizing controllers that guarantee collision avoidance and goal stabilization for multiple robots. However, it has been noted that reactive control synthesis methods (such as CBFs) are prone to deadlock, an equilibrium of system dynamics that causes robots to come to a standstill before reaching their goals. In this paper, we formally derive characteristics of deadlock in a multirobot system that uses CBFs. We propose a novel approach to analyze deadlocks resulting from optimization based controllers (CBFs) by borrowing tools from duality theory and graph enumeration. Our key insight is that system deadlock is characterized by a force-equilibrium on robots and we show how complexity of deadlock analysis increases approximately exponentially with the number of robots. This analysis allows us to interpret deadlock as a subset of the state space, and we prove that this set is non-empty, bounded and located on the boundary of the safety set. Finally, we use these properties to develop a provably correct decentralized algorithm for deadlock resolution which ensures that robots converge to their goals while avoiding collisions. We show simulation results of the resolution algorithm for two and three robots and experimentally validate this algorithm on Khepera-IV robots.


Imitation Learning as f-Divergence Minimization

Liyiming Ke, Sanjiban Choudhury, Matt Barnes, Wen Sun, Gilwoo Lee and Siddhartha Srinivasa

Abstract

We address the problem of imitation learning with multi-modal demonstrations. Instead of attempting to learn all modes, we argue that in many tasks it is sufficient to imitate any one of them. We show that the state-of-the-art methods such as GAIL and behavior cloning, due to their choice of loss function, often incorrectly interpolate between such modes. Our key insight is to minimize the right divergence between the learner and the expert state-action distributions, namely the reverse KL divergence or I-projection. We propose a general imitation learning framework for estimating and minimizing any f-Divergence. By plugging in different divergences, we are able to recover existing algorithms such as Behavior Cloning (Kullback-Leibler), GAIL (Jensen Shannon) and DAGGER (Total Variation). Empirical results show that our approximate I-projection technique is able to imitate multi-modal behaviors more reliably than GAIL and behavior cloning.


Approximation Algorithms for Distributed Multi-Robot Coverage in Non-Convex Environments

Armin Sadeghi, Ahmad Bilal Asghar and Stephen L. Smith

Abstract

In this paper, we revisit the distributed coverage control problem with multiple robots on both metric graphs and in non-convex continuous environments. Traditionally, the solutions provided for this problem converge to a locally optimal solution with no guarantees on the quality of the solution. We consider sub-additive sensing functions, which capture the scenarios where sensing an event requires the robot to visit the event location. For these sensing functions, we provide the first constant factor approximation algorithms for the distributed coverage problem. The approximation results require twice the conventional communication range in the existing coverage algorithms. However, we show through extensive simulation results that the proposed approximation algorithms outperform several existing algorithms in convex, non-convex continuous, and discrete environments even with the conventional communication ranges. Moreover, the proposed algorithms match the state-of-the-art centralized algorithms in the solution quality.


The Surprising Effectiveness of Linear Models for Visual Foresight in Object Pile Manipulation

H.J. Terry Suh and Russ Tedrake

Abstract

In this paper, we tackle the problem of pushing piles of small objects into a desired target set using visual feedback. Unlike conventional single-object manipulation pipelines, which estimate the state of the system parametrized by pose, the underlying physical state of this system is difficult to observe from images. Thus, we take the approach of reasoning directly in the space of images, and acquire the dynamics of visual measurements in order to synthesize a visual-feedback policy. We present a simple controller using an image-space Lyapunov function, and evaluate the closed-loop performance using three different class of models for image prediction: deep-learning-based models for image-to-image translation, an object-centric model obtained from treating each pixel as a particle, and a switched-linear system where an action-dependent linear map is used. Through results in simulation and experiment, we show that for this task, a linear model works surprisingly well — achieving better prediction error, downstream task performance, and generalization to new environments than the deep models we trained on the same amount of data. We believe these results provide an interesting example in the spectrum of models that are most useful for vision-based feedback in manipulation, considering both the quality of visual prediction, as well as compatibility with rigorous methods for control design and analysis.


Forward Chaining Hierarchical Partial-Order Planning

Andrew Messing and Seth Hutchinson

Abstract

In recent years, the surge in interest in integrated Task and Motion Planning (TAMP) has caused a resurgence in Task Planning research in the robotics community. Meanwhile, in the broader AI community, combining partial-order planning with grounded forward chaining has become popular for temporal task planning, preserving the ability of partial-order planners to deal with concurrent actions while exploiting the speed of modern-day grounded forward search. In this paper, we present two new planning algorithms. The first, FCPOP, combines full utilization of the delayed action ordering commitment of partial-order planning with grounded forward search guided by a temporally informed heuristic. This results in a planner that is flexible in how it structures plans with respect to action parallelism, creates high-quality plans with low makespans, and computes plans quickly. FCPOP is shown empirically to outperform state-of-the-art temporal planners on several benchmark planning problems. The second planning algorithm FCHPOP introduces hierarchical information in the form of abstract actions. This reduces the number of nodes that need to be explored and speeds up the planning process while still generating quality plans.


Learning Control Sets for Lattice Planners from User Preferences

Alexander Botros, Nils Wilde and Stephen L. Smith

Abstract

This work investigates the design of a motion planner that can capture user preferences. In detail, we generate a sparse control set for a lattice planner which closely follows the preferences of a user. Given a set of demonstrated trajectories from a single user, we estimate user preferences based on a weighted sum of trajectory features. We then optimize a set of connections in the lattice of given size for the user cost function. The restricted number of connections limits the branching factor, ensuring strong performance during subsequent motion planning. Further, every trajectory in the control set reflects the learned user preference while the sub-optimality due to the size restriction is minimized. We show that this problem is optimally solved by applying a separation principle: First, we find the best estimate of the user cost function given the data, then an optimal control set is computed given that estimate. We evaluate our work in a simulation for an autonomous robot in a four-dimensional spatiotemporal lattice and show that the proposed approach is suitable to replicate the demonstrated behaviour while enjoying substantially increased performance.


Active localization of multiple targets from noisy relative measurements

Selim Engin and Volkan Isler

Abstract

Consider a mobile robot tasked with localizing targets at unknown locations by obtaining relative measurements. The observations can be bearing or range measurements. How should the robot move so as to localize the targets and minimize the uncertainty in their locations as quickly as possible? Most existing approaches are either greedy in nature or rely on accurate initial estimates.

We formulate this path planning problem as an unsupervised learning problem where the measurements are aggregated using a Bayesian histogram filter. The robot learns to minimize the total uncertainty of each target in the shortest amount of time using the current measurement and an aggregate representation of the current belief state. We analyze our method in a series of experiments where we show that our method outperforms a standard greedy approach. In addition, its performance is also comparable to an offline algorithm which has access to the true location of the targets.


Experiments with Tractable Feedback in Robotic Planning under Uncertainty: Insights over a wide range of noise regimes

Mohamed Naveed Gul Mohamed, Suman Chakravorty and Dylan A. Shell

Abstract

We consider the problem of robotic planning under uncertainty. This problem may be posed as a stochastic optimal control problem, complete solution to which is fundamentally intractable owing to the infamous curse of dimensionality. We report the results of an extensive simulation study in which we have compared two methods, both of which aim to salvage tractability by using alternative, albeit inexact, means for treating feedback. The first is a recently proposed method based on a near-optimal “decoupling principle” for tractable feedback design, wherein a nominal open-loop problem is solved, followed by a linear feedback design around the open-loop. The second is Model Predictive Control (MPC), a widely-employed method that uses repeated re-computation of the nominal open-loop problem during execution to correct for noise, though when interpreted as feedback, this can only said to be an implicit form. We examine a much wider range of noise levels than have been previously reported and empirical evidence suggests that the decoupling method allows for tractable planning over a wide range of uncertainty conditions without unduly sacrificing performance.


Back-propagation through Signal Temporal Logic Specifications: Infusing Logical Structure into Gradient-Based Methods

Karen Leung, Nikos Arechiga and Marco Pavone

Abstract

This paper presents a technique, named stlcg, to compute the quantitative semantics of Signal Temporal Logic (STL) formulas using computation graphs. This provides a platform which enables the incorporation of logic-based specifications into robotics problems that benefit from gradient-based solutions. Specifically, STL is a powerful and expressive formal language that can specify spatial and temporal properties of signals generated by both continuous and hybrid systems. The quantitative semantics of STL provide a robustness metric, i.e., how much a signal satisfies or violates an STL specification. In this work we devise a systematic methodology for translating STL robustness formulas into computation graphs. With this representation, and by leveraging off-the-shelf auto-differentiation tools, we are able to back-propagate through STL robustness formulas and hence enable a natural and easy-to-use integration with many gradient-based approaches used in robotics. We demonstrate, through examples stemming from various robotics applications, that stlcg is versatile, computationally efficient, and capable of injecting human-domain knowledge into the problem formulation.


Hybrid Control for Learning Motor Skills

Ian Abraham, Alexander Broad, Allison Pinosky, Brenna Argall and Todd D. Murphey

Abstract

We develop a hybrid control approach for robot learning based on combining learned predictive models with experience-based state-action policy mappings to improve the learning capabilities of robotic systems. Predictive models provide an understanding of the task and the physics (which improves sample-efficiency), while experience-based policy mappings are treated as “muscle memory” that encode favorable actions as experiences that override planned actions. Hybrid control tools are used to create an algorithmic approach for combining learned predictive models with experience-based learning. Hybrid learning is presented as a method for efficiently learning motor skills by systematically combining and improving the performance of predictive models and experience-based policies. A deterministic variation of hybrid learning is derived and extended into a stochastic implementation that relaxes some of the key assumptions in the original derivation. Each variation is tested on experience-based learning methods (where the robot interacts with the environment to gain experience) as well as imitation learning methods (where experience is provided through demonstrations and tested in the environment). The results show that our method is capable of improving the performance and sample-efficiency of learning motor skills in a variety of experimental domains.


Pushing the Boundaries of Asymptotic Optimality in Integrated Task and Motion Planning

Rahul Shome, Daniel Nakhimovich and Kostas E. Bekris

Abstract

Integrated task and motion planning problems describe a multi-modal state space, which is often abstracted as a set of smooth manifolds that are connected via sets of transitions states. One approach to solving such problems is to sample reachable states in each of the manifolds, while simultaneously sampling transition states. Prior work has shown that in order to achieve asymptotically optimal (AO) solutions for such piecewise-smooth task planning problems, it is sufficient to double the connection radius required for AO sampling-based motion planning. This was shown under the assumption that the transition sets themselves are smooth. The current work builds upon this result and demonstrates that it is sufficient to use the same connection radius as for standard AO motion planning. Furthermore, the current work studies the case that the transition sets are non-smooth boundary points of the valid state space, which is frequently the case in practice, such as when a gripper grasps an object. This paper generalizes the notion of clearance that is typically assumed in motion and task planning to include such individual, potentially non-smooth transition states. It is shown that asymptotic optimality is retained under this generalized regime.


Efficient Contact Mode Enumeration in 3D

Eric Huang, Xianyi Cheng and Mathew T. Mason

Abstract

In a hybrid dynamical system with multiple rigid bodies, the relative motions of the contact points on two colliding bodies may be classified as separating, sticking (moving together), or sliding. Given a physical contact model, the active contact modes determine the dynamic equations of motion. Analogously, the set of all possible (valid) contact mode assignments enumerates the set of all possible dynamical flows of the hybrid dynamical system at a given state. Naturally, queries about the kinematics or dynamics of the system can be framed as computations over the set of possible contact modes. This paper investigates efficient ways to compute this set.

To that end, we have developed the first efficient 3D contact mode enumeration algorithm. The algorithm is exponential in the degrees of freedom of the system and polynomial in the number of contacts. The exponential term is unavoidable and an example is provided. Prior work in this area has only demonstrated efficient contact mode enumeration in 2D for a single rigid body. We validated our algorithm on peg-in-hole, boxes against walls, and a robot hand grasping an ellipse. Our experimental results indicate real-time contact mode enumeration is possible for small to medium sized systems. Finally, this paper concludes with a discussion of possible related application areas for future work. Ultimately, the goal of this paper is to provide a novel computational tool for researchers to use to simulate, analyze, and control robotic systems that make and break contact with the environment.


Visualizing Local Minima in Multi-Robot Motion Planning using Multilevel Morse Theory

Andreas Orthey and Marc Toussaint

Abstract

Multi-robot motion planning problems often have many local minima. It is essential to visualize those local minima such that we can better understand, debug and interact with multi-robot systems. Towards this goal, we present the multi-robot motion explorer, an algorithm which extends previous results on multilevel Morse theory by introducing a component-based framework, where we reduce multi-robot configuration spaces by reducing each robots component space using fiber bundles. Our algorithm exploits this component structure to search for and visualize local minima. A user of the algorithm can specify a multilevel abstraction and an optimization algorithm. We use this information to incrementally build a local minima tree for a given problem. We demonstrate this algorithm on several multi-robot systems of up to 20 degrees of freedom.


On Rearrangement of Items Stored in Stacks

Mario Szegedy and Jingjin Yu

Abstract

There are n ≥ 2 stacks, each filled with d items, and one empty stack. Every stack has capacity d > 0. A robot arm, in one stack operation (step), may pop one item from the top of a non-empty stack and subsequently push it onto a stack not at capacity. In a labeled problem, all nd items are distinguishable and are initially randomly scattered in the n stacks. The items must be rearranged using pop-and-pushs so that in the end, the k th stack holds items (k – 1)d + 1, …, kd, in that order, from the top to the bottom for all 1 ≤ k ≤ n. In an unlabeled problem, the nd items are of n types of d each. The goal is to rearrange items so that items of type k are located in the kth stack for all 1 ≤ k ≤ n. In carrying out the rearrangement, a natural question is to find the least number of required pop-and-pushes.

Our main contributions are: (1) an algorithm for restoring the order of n2 items stored in an n × n table using only 2n column and row permutations, and its generalization, and (2) an algorithm with a guaranteed upper bound of O(nd) steps for solving both versions of the stack rearrangement problem when d ≤ ⌈cn⌉ for arbitrary fixed positive number c. In terms of the required number of steps, the labeled and unlabeled version have lower bounds Ω(nd + nd log d/log n) and Ω(nd), respectively.


Approximation Algorithms for the Single Robot Line Coverage Problem

Saurav Agarwal and Srinivas Akella

Abstract

The line coverage problem is the task of servicing a given set of one-dimensional features in an environment. Its applications include the inspection of road networks, power lines, and oil and gas lines. We model the problem, for the case of a single robot, as an optimization problem that minimizes the total cost of travel on a given graph. The line coverage problem is a generalization of the standard arc routing problems, and is NP-hard in general. We consider here the line coverage problem for a single robot where the service and deadhead costs are treated separately, and are asymmetric. We present approximation algorithms to obtain bounded solutions efficiently, using the minimum cost ow problem.We build the main algorithm in stages by considering three simpler subproblems. The subproblems are based on the structure of the required graph, i.e., the graph induced by the features that require servicing. We first present an optimal algorithm for the case of Eulerian graphs with only required edges. Next we consider general graphs, not necessarily Eulerian, with only required edges and present a 2-approximation algorithm. Finally, we consider the general case with both required and non-required edges. The approximation algorithm is dependent on the asymmetric traveling salesperson problem (ATSP), and is bounded by α(C) + 2, where α(C) is the approximation factor of the ATSP algorithm with C connected components. Our upper bound is also an improvement over the existing results for the asymmetric rural postman problem.


Scalable Low-Rank Semidefinite Programming for Certifiably Correct Machine Perception

David M. Rosen

Abstract

Semidefinite relaxation has recently emerged as a powerful technique for machine perception, in many cases enabling the recovery of certifiably globally optimal solutions of generally-intractable nonconvex estimation problems. However, the high computational cost of standard interior-point methods for semidefinite optimization prevents these algorithms from scaling effectively to the high-dimensional problems frequently encountered in machine perception tasks. To address this challenge, in this paper we present an efficient algorithm for solving the large-scale but low-rank semidefinite relaxations that underpin current certifiably correct machine perception methods. Our algorithm preserves the scalability of current state-of-the-art low-rank semidefinite optimizers that are custom-built for the geometry of specific machine perception problems, but generalizes to a broad class of convex programs over spectrahedral sets without the need for detailed manual analysis or design. The result is an easy-to-use, general-purpose computational tool capable of supporting the development and deployment of a broad class of novel certifiably correct machine perception methods.