diff --git a/Project.toml b/Project.toml index 760d2781..572d6eb8 100644 --- a/Project.toml +++ b/Project.toml @@ -1,6 +1,6 @@ name = "TrajectoryOptimization" uuid = "c79d492b-0548-5874-b488-5a62c1d9d0ca" -version = "0.3.1" +version = "0.3.2" [deps] DocStringExtensions = "ffbed154-4ef7-542d-bbb7-c09d3a79fcae" diff --git a/README.md b/README.md index c159475a..1d37cd36 100644 --- a/README.md +++ b/README.md @@ -4,17 +4,9 @@ | -------------- | --------------- | |   [](https://codecov.io/gh/RoboticExplorationLab/TrajectoryOptimization.jl) | [](https://RoboticExplorationLab.github.io/TrajectoryOptimization.jl/dev) [](https://RoboticExplorationLab.github.io/TrajectoryOptimization.jl/stable) | -A library of solvers for trajectory optimization problems written in Julia. Currently, the following methods are implemented with a common interface: +This package is built for the express purpose of defining and evaluating trajectory optimization problems. Although early versions (pre v0.3) also included methods to solve these problems, this is now left to separate packages that implement the interface defined in TrajectoryOptimization.jl. For example, [Altro.jl](https://github.com/RoboticExplorationLab/Altro.jl) implements the ALTRO solver that used to be included in TrajectoryOptimization.jl. This change was done to make this package lighter and allow more abstraction in how solvers set up and solve the problems defined by this package. -[ALTRO (Augmented Lagrangian TRajectory Optimizer)](https://rexlab.stanford.edu/papers/altro-iros.pdf): A fast solver for constrained trajectory optimization problems formulated as MDPs that features: - * General nonlinear cost functions, including minimum time problems - * General nonlinear state and input constraints - * Infeasible state initialization - * Square-root methods for improved numerical conditioning - * Active-set projection method for solution polishing - -Direct Collocation (DIRCOL) - * Interfaces to Nonlinear Programming solvers (e.g., [Ipopt](https://github.com/coin-or/Ipopt), [SNOPT](https://ccom.ucsd.edu/~optimizers/solvers/snopt/)) via [MathOptInterface](https://github.com/JuliaOpt/MathOptInterface.jl) +TrajectoryOptimization.jl aims to provide both a convenient API for setting up and defining trajectory optimization problem and extremely efficient methods for evaluating them. Nearly all of the methods implemented have zero memory allocations and have been highly optimized for speed. Since trajectory optimization problem have a unique structure that set them apart from generic NLPs (nonlinear programs), use of the specialized methods in TrajectoryOptimization.jl can provide dramatic improvements in the computational efficiency of the solvers that implement the API. All methods utilize Julia's extensive autodifferentiation capabilities via [ForwardDiff.jl](http://www.juliadiff.org/ForwardDiff.jl/) so that the user does not need to specify derivatives of dynamics, cost, or constraint functions. @@ -27,56 +19,10 @@ Pkg.add("TrajectoryOptimization") # What's New `TrajectoryOptimization.jl` underwent significant changes between versions `v0.1` and `v0.2`. The new code is significantly faster (up to 100x faster). The core part of the ALTRO solver (everything except the projected newton phase) is completely allocation-free once the solver has been initialized. Most of the API has changed significantly. See the documentation for more information on the new API. -## Quick Start -To run a simple example of a constrained 1D block move (see script in `/examples/quickstart.jl`): -```julia -using TrajectoryOptimization -using StaticArrays -using LinearAlgebra -const TO = TrajectoryOptimization - -struct DoubleIntegrator{T} <: AbstractModel - mass::T -end - -function TO.dynamics(model::DoubleIntegrator, x, u) - SA[x[2], u[1] / model.mass] -end - -Base.size(::DoubleIntegrator) = 2,1 - -# Model and discretization -model = DoubleIntegrator(1.0) -n,m = size(model) -tf = 3.0 # sec -N = 21 # number of knot points +In `v0.3` the package was split into several different packages for increased modularity. These include [RobotDynamics.jl](https://github.com/RoboticExplorationLab/RobotDynamics.jl), [Altro.jl](https://github.com/RoboticExplorationLab/Altro.jl), [RobotZoo.jl](https://github.com/bjack205/RobotZoo.jl), and [TrajOptPlots.jl](https://github.com/RoboticExplorationLab/TrajOptPlots.jl). -# Objective -x0 = SA[0,0.] # initial state -xf = SA[1,0.] # final state - -Q = Diagonal(@SVector ones(n)) -R = Diagonal(@SVector ones(m)) -obj = LQRObjective(Q, R, N*Q, xf, N) - -# Constraints -cons = TO.ConstraintSet(n,m,N) -add_constraint!(cons, GoalConstraint(xf), N:N) -add_constraint!(cons, BoundConstraint(n,m, u_min=-10, u_max=10), 1:N-1) - -# Create and solve problem -prob = Problem(model, obj, xf, tf, x0=x0, constraints=cons) -solver = ALTROSolver(prob) -cost(solver) # initial cost -solve!(solver) # solve with ALTRO -max_violation(solver) # max constraint violation -cost(solver) # final cost -iterations(solver) # total number of iterations - -# Get the state and control trajectories -X = states(solver) -U = controls(solver) -``` +## Quick Start +To run a simple example of a constrained 1D block move see script in [`/examples/quickstart.jl`](https://github.com/RoboticExplorationLab/TrajectoryOptimization.jl/blob/master/examples/quickstart.jl). ## Examples Notebooks with more detailed examples can be found [here](https://github.com/RoboticExplorationLab/TrajectoryOptimization.jl/tree/master/examples) diff --git a/src/conset.jl b/src/conset.jl index a36e92d7..2281da32 100644 --- a/src/conset.jl +++ b/src/conset.jl @@ -49,7 +49,11 @@ end # Max values function max_violation(conSet::AbstractConstraintSet) max_violation!(conSet) - return maximum(conSet.c_max) + if isempty(conSet) + return 0 + else + return maximum(conSet.c_max) + end end function max_violation!(conSet::AbstractConstraintSet) diff --git a/src/constraint_list.jl b/src/constraint_list.jl index d218b83a..9486bd2f 100644 --- a/src/constraint_list.jl +++ b/src/constraint_list.jl @@ -106,6 +106,9 @@ cons_and_inds[1] == (bnd,1:n-1) # (true) function add_constraint!(cons::ConstraintList, con::AbstractConstraint, inds::UnitRange{Int}, idx=-1) @assert check_dims(con, cons.n, cons.m) "New constaint not consistent with n=$(cons.n) and m=$(cons.m)" @assert inds[end] <= length(cons.p) "Invalid inds, inds[end] must be less than number of knotpoints, $(length(cons.p))" + if isempty(cons) + idx = -1 + end if idx == -1 push!(cons.constraints, con) push!(cons.inds, inds) diff --git a/src/problem.jl b/src/problem.jl index 724fdd86..f09071e4 100644 --- a/src/problem.jl +++ b/src/problem.jl @@ -241,7 +241,7 @@ Simulate the dynamics forward from the initial condition `x0` using the controls trajectory `Z`. If a problem is passed in, `Z = prob.Z`, `model = prob.model`, and `x0 = prob.x0`. """ -@inline rollout!(prob) = rollout!(get_model(prob), get_trajectory(prob), get_initial_state(prob)) +@inline rollout!(prob::Problem{Q}) where {Q} = rollout!(Q, get_model(prob), get_trajectory(prob), get_initial_state(prob)) function Problem(p::Problem; model=p.model, obj=p.obj, constraints=p.constraints, x0=p.x0, xf=p.xf, t0=p.t0, tf=p.tf)
Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.
Alternative Proxies: