TrajectoryOptimization defines a particular type of nonlinear programing problem — trajectory optimization problem. More...

Inheritance diagram for TrajectoryOptimization:
[legend]

Public Member Functions

 TrajectoryOptimization (char name,DynamicalSystem plant,integerConstantTimeHorizon num_grid,struct bounds,varargin varargin)
 The constructor function. More...
 
function obj = update ()
 Updates the NLP problems before load it to NLP solver. More...
 
function obj = configure (struct bounds, varargin)
 configure the trajectory optimizatino NLP problem More...
 
function  compileConstraint (cellstr constr,char export_path,cellstr exclude,varargin varargin)
 Compile and export symbolic expression and derivatives of all NLP functions. More...
 
function  compileObjective (cellstr cost,char export_path,cellstr exclude,varargin varargin)
 Compile and export symbolic expression and derivatives of all NLP functions. More...
 
function obj = addVariable (char label,rowvec nodes, varargin)
 Adds NLP decision variables. More...
 
function obj = removeVariable (char label)
 Removes a NLP optimization variable. More...
 
function obj = addInputVariable (struct bounds)
 Adds input variables as the NLP decision variables to the problem. More...
 
function obj = addParamVariable (struct bounds)
 Adds parameters as the NLP decision variables to the problem. More...
 
function obj = addStateVariable (struct bounds)
 Adds state variables as the NLP decision variables to the problem. More...
 
function obj = addTimeVariable (struct bounds)
 Adds time as the NLP decision variables to the problem. More...
 
function obj = updateVariableProp (char label,char node, varargin)
 This function updates the properties of the NLP variable objects based on the input name-value pair arguments. More...
 
function obj = configureVariables (struct bounds)
 This function configures the structure of the optimization variable by adding (registering) them to the optimization variable table. More...
 
function obj = updateVariableBounds (bounds)
 This function updates the boundary conditions of the optimization variable by updating corresponding NLP variables. More...
 
function fcstr = directCollocation (char name,SymVariable x,SymVariable dx)
 Return the SymFunction object of the direct collocation constraint given the state (x) and derivatives (dx). More...
 
function obj = addConstraint (char label,rowvec nodes,struct cstr_array)
 Add NLP constraints constraints. More...
 
function obj = addCollocationConstraint ()
 Add direct collocation equations as a set of equality constraints. More...
 
function obj = addDynamicsConstraint ()
 Add system dynamics equations as a set of equality constraints. More...
 
function obj = addNodeConstraint (SymFunction func,cellstr deps,char nodes,colvec lb,colvec ub,char type,double auxdata)
 Add NLP constraint function that only depends on variables at a particular node. The input argument 'nodes' will specify at which nodes the function is defined. More...
 
function obj = updateConstrProp (char label,char node, varargin)
 This function updates the properties of the constraint objects based on the input name-value pair arguments. More...
 
function obj = removeConstraint (char label)
 Removes a group of NLP constraints. More...
 
function obj = addCost (char label,rowvec nodes,struct cost_array)
 Add NLP object functions. More...
 
function obj = addRunningCost (SymFunction func,cellstr deps,double auxdata)
 Add a running cost to the problem. More...
 
function obj = addNodeCost (SymFunction func,cellstr deps,char node,double auxdata)
 Add a cost function that only depends on variables at a particular node. The input argument 'nodes' will specify at which nodes the function is defined. More...
 
function obj = updateCostProp (char label,char node, varargin)
 This function updates the properties of the cost function objects based on the input name-value pair arguments. More...
 
function obj = removeCost (label)
 Removes a group of NLP cost functions. More...
 
function [ yc , cl , cu ] = checkConstraints (x, tol, output_file, permission)
 Check the violation of the constraints. More...
 
function yc = checkCosts (x, output_file, permission)
 Check the value of const function. More...
 
function  checkVariables (x, tol, output_file, permission)
 Check the violation of the constraints. More...
 
function [ tspan , states , inputs , params ] = exportSolution (colvec sol,double t0)
 Analyzes the solution of the NLP problem. More...
 
- Public Member Functions inherited from NonlinearProgram
 NonlinearProgram (name)
 The default class constructor function. More...
 
function obj = regVariable (NlpVariable vars)
 This method registers the information of an optimization variable. More...
 
function obj = update ()
 Updates the NLP problems before load it to NLP solver. More...
 
function obj = regObjective (NlpFunction funcs)
 This method registers the information of a NLP function as a cost function. More...
 
function obj = regConstraint (NlpFunction funcs)
 This method registers the information of a NLP function as a constraint. More...
 
function [ nVar , lowerbound , upperbound ] = getVarInfo ()
 The function returns the dimension, upper/lower limits of NLP variables. More...
 
function x0 = getInitialGuess (char method)
 This function returns an initial guess for the NLP. More...
 
function obj = setOption (varargin)
 Sets the object options, and return the complete list of option structure including unchanged default options. More...
 
function  compileConstraint (char export_path,varargin varargin)
 Compile and export symbolic expression and derivatives of all NLP functions. More...
 
function  compileObjective (char export_path,varargin varargin)
 Compile and export symbolic expression and derivatives of all NLP functions. More...
 

Public Attributes

integer NumNode
 The number of discrete nodes along the trajectory. More...
 
table OptVarTable
 A table of NLP decision variables. The row determines the identity of the variable, and the column determines at which node the variable is defined. More...
 
table ConstrTable
 A table of NLP constraints. The row determines the identity of the constraint, and the column determines at which node the constraint is defined. More...
 
table CostTable
 A table of cost functions. The row determines the identity of the function, and the column determines at which node the variable is defined. More...
 
DynamicalSystem Plant
 The dynamical system plant of the interest. More...
 
- Public Attributes inherited from NonlinearProgram
char Name
 The name of the problem. More...
 
struct Options
 The class option. More...
 
NlpVariable VariableArray
 An array contains all information regarding NLP optimization variables. More...
 
NlpFunction CostArray
 An array data stores objective functions. More...
 
NlpFunction ConstrArray
 A cell array data stores all constraints functions. More...
 
 Sol
 The solution of the NLP problem. More...
 
- Public Attributes inherited from handle
 addlistener
 Creates a listener for the specified event and assigns a callback function to execute when the event occurs. More...
 
 notify
 Broadcast a notice that a specific event is occurring on a specified handle object or array of handle objects. More...
 
 delete
 Handle object destructor method that is called when the object's lifecycle ends. More...
 
 disp
 Handle object disp method which is called by the display method. See the MATLAB disp function. More...
 
 display
 Handle object display method called when MATLAB software interprets an expression returning a handle object that is not terminated by a semicolon. See the MATLAB display function. More...
 
 findobj
 Finds objects matching the specified conditions from the input array of handle objects. More...
 
 findprop
 Returns a meta.property objects associated with the specified property name. More...
 
 fields
 Returns a cell array of string containing the names of public properties. More...
 
 fieldnames
 Returns a cell array of string containing the names of public properties. See the MATLAB fieldnames function. More...
 
 isvalid
 Returns a logical array in which elements are true if the corresponding elements in the input array are valid handles. This method is Sealed so you cannot override it in a handle subclass. More...
 
 eq
 Relational functions example. See details for more information. More...
 
 transpose
 Transposes the elements of the handle object array. More...
 
 permute
 Rearranges the dimensions of the handle object array. See the MATLAB permute function. More...
 
 reshape
 hanges the dimensions of the handle object array to the specified dimensions. See the MATLAB reshape function. More...
 
 sort
 ort the handle objects in any array in ascending or descending order. More...
 

Static Public Attributes

static const ::double DefaultNumberOfGrid = 10
 The default number of collocation grids. More...
 

Detailed Description

TrajectoryOptimization defines a particular type of nonlinear programing problem — trajectory optimization problem.

See also
NonlinearProgram, HybridSystem
Author
ayonga
Date
2016-10-26

Copyright (c) 2016, AMBER Lab All right reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted only in compliance with the BSD 3-Clause license, see http://www.opensource.org/licenses/bsd-license.php

Constructor & Destructor Documentation

◆ TrajectoryOptimization()

TrajectoryOptimization.TrajectoryOptimization ( char  name,
DynamicalSystem  plant,
integerConstantTimeHorizon  num_grid,
struct  bounds,
varargin  varargin 
)
inline

The constructor function.

Parameters
namethe name of the problem
plantthe dynamical system plant
num_gridthe number of grids along the trajectory
boundsa structed data stores the boundary information of the NLP variables
vararginuser-defined options for the problem
TrajectoryOptimization ( ..., [ "CollocationScheme", CollocationScheme_value ] [, "DistributeParameters", DistributeParameters_value ]
[, "DistributeTimeVariable", DistributeTimeVariable_value ] [, "ConstantTimeHorizon", ConstantTimeHorizon_value ]
[, "DerivativeLevel", DerivativeLevel_value ] [, "EqualityConstraintBoundary", EqualityConstraintBoundary_value ] )
Named Parameters for varargin:
  • CollocationScheme CollocationScheme ( Default: HermiteSimpson )
  • DistributeParameters DistributeParameters ( Default: true )
  • DistributeTimeVariable DistributeTimeVariable ( Default: true )
  • ConstantTimeHorizon ConstantTimeHorizon ( Default: nan(2,1) )
  • DerivativeLevel DerivativeLevel ( Default: 1 )
  • EqualityConstraintBoundary EqualityConstraintBoundary ( Default: 0 )

Member Function Documentation

◆ addCollocationConstraint()

function obj = TrajectoryOptimization.addCollocationConstraint ( )

Add direct collocation equations as a set of equality constraints.

Todo:
implement pseudospectral method

◆ addConstraint()

function obj = TrajectoryOptimization.addConstraint ( char  label,
rowvec  nodes,
struct  cstr_array 
)

Add NLP constraints constraints.

See also
NlpFunction, removeConstraint
Note
Parameters
labelthe label name (column) of the constraints
nodesthe node list of the variable
cstr_arrayan array of structures that could be used to construct the NlpFunction object.

◆ addCost()

function obj = TrajectoryOptimization.addCost ( char  label,
rowvec  nodes,
struct  cost_array 
)

Add NLP object functions.

See also
NlpFunction, removeCost
Note
Parameters
labelthe label name (column) of the cost
nodesthe node list of the variable
cost_arrayan array of structures that could be used to construct the NlpFunction object.

◆ addDynamicsConstraint()

function obj = TrajectoryOptimization.addDynamicsConstraint ( )

Add system dynamics equations as a set of equality constraints.

◆ addInputVariable()

function obj = TrajectoryOptimization.addInputVariable ( struct  bounds)

Adds input variables as the NLP decision variables to the problem.

Note
The input variables may includes the control inputs, as well as external forces such as disturbance or contact wrenches.
Parameters
boundsa structed data stores the boundary information of the NLP variables
Required fields of bounds:

◆ addNodeConstraint()

function obj = TrajectoryOptimization.addNodeConstraint ( SymFunction  func,
cellstr  deps,
char  nodes,
colvec  lb,
colvec  ub,
char  type,
double  auxdata 
)

Add NLP constraint function that only depends on variables at a particular node. The input argument 'nodes' will specify at which nodes the function is defined.

Note
This function provides a simple type of constraints function which dependends only on variables at same particular node.
Attention
In the case the constraints function dependes on variables at different nodes, please use the basic 'addCost' method directly.
This method can be used to add any terminal constraint by specify 'nodes' as either 'first' or 'last'.
Parameters
funca symbolic function of the constraint
depsa list of dependent variables
nodesan indicator of first or last node
lbthe lower bound of the constraints
ubthe upper bound of the constraints
typethe type of the constraints ('Linear' or 'Nonlinear')
auxdataauxilary constant data to be feed in the function
Required fields of func:

References implode().

◆ addNodeCost()

function obj = TrajectoryOptimization.addNodeCost ( SymFunction  func,
cellstr  deps,
char  node,
double  auxdata 
)

Add a cost function that only depends on variables at a particular node. The input argument 'nodes' will specify at which nodes the function is defined.

Note
This function provides a simple type of cost function which dependends only on variables at some particular node. If multiple nodes are specified, the final cost function will be the sum of the function computated at each node.
Attention
In the case the cost function dependes on variables at different nodes, please use the basic 'addCost' method directly.
This method can be used to add any terminal cost function by specify 'nodes' as either 'first' or 'last'.
Parameters
funca symbolic function to be integrated
depsa list of dependent variables
auxdataauxilary constant data to be feed in the function
nodean indicator of first or last node
Required fields of func:

References implode().

◆ addParamVariable()

function obj = TrajectoryOptimization.addParamVariable ( struct  bounds)

Adds parameters as the NLP decision variables to the problem.

Parameters
boundsa structed data stores the boundary information of the NLP variables

◆ addRunningCost()

function obj = TrajectoryOptimization.addRunningCost ( SymFunction  func,
cellstr  deps,
double  auxdata 
)

Add a running cost to the problem.

Parameters
funca symbolic function to be integrated
depsa list of dependent variables
auxdataauxilary constant data to be feed in the function
Required fields of func:

◆ addStateVariable()

function obj = TrajectoryOptimization.addStateVariable ( struct  bounds)

Adds state variables as the NLP decision variables to the problem.

Parameters
boundsa structed data stores the boundary information of the NLP variables

◆ addTimeVariable()

function obj = TrajectoryOptimization.addTimeVariable ( struct  bounds)

Adds time as the NLP decision variables to the problem.

Parameters
boundsa structed data stores the boundary information of the NLP variables
Required fields of bounds:

◆ addVariable()

function obj = TrajectoryOptimization.addVariable ( char  label,
rowvec  nodes,
  varargin 
)

Adds NLP decision variables.

See also
NlpVariable, removeVariable
Parameters
labelthe label name (column) of the variable
nodesthe node list of the variable
vararginvariable input arguments for property values non-empty NlpVariables This function updates the properties of the class object based on the input name-value pair arguments.
vararginvariable nama-value pair input arguments, in detail:
updateProp ( lb, ub, x0 )
Required Parameters for varargin:
  • lb lower limit
  • ub upper limit
  • x0 a typical value of the variable

◆ checkConstraints()

function [ yc , cl , cu ] = TrajectoryOptimization.checkConstraints (   x,
  tol,
  output_file,
  permission 
)

Check the violation of the constraints.

◆ checkCosts()

function yc = TrajectoryOptimization.checkCosts (   x,
  output_file,
  permission 
)

Check the value of const function.

◆ checkVariables()

function TrajectoryOptimization.checkVariables (   x,
  tol,
  output_file,
  permission 
)

Check the violation of the constraints.

◆ compileConstraint()

function TrajectoryOptimization.compileConstraint ( cellstr  constr,
char  export_path,
cellstr  exclude,
varargin  varargin 
)

Compile and export symbolic expression and derivatives of all NLP functions.

Note
If constr is emtpy, then it will compile all constraints.
Parameters
constra list of constraints to be compiled
export_paththe path to export the file
excludea list of functions to be excluded
vararginvariable input parameters
compileConstraint ( ..., StackVariable, ForceExport, BuildMex, Namespace )
Required Parameters for varargin:
  • StackVariable whether to stack variables into one
  • ForceExport force the export
  • BuildMex flag whether to MEX the exported file
  • Namespace the namespace of the function

◆ compileObjective()

function TrajectoryOptimization.compileObjective ( cellstr  cost,
char  export_path,
cellstr  exclude,
varargin  varargin 
)

Compile and export symbolic expression and derivatives of all NLP functions.

Note
If cost is emtpy, then it will compile all cost functions.
Parameters
costthe cost function to be compiled
export_paththe path to export the file
excludea list of functions to be excluded
vararginvariable input parameters
compileObjective ( ..., ForceExport, BuildMex )
Required Parameters for varargin:
  • ForceExport force the export
  • BuildMex flag whether to MEX the exported file

◆ configure()

function obj = TrajectoryOptimization.configure ( struct  bounds,
  varargin 
)

configure the trajectory optimizatino NLP problem

This process will add NLP variables based on the information of the dynamical system object, impose dynamical and collocation constraints, then call the system constraints callback function to add any system-specific constraints.

Parameters
boundsa struct data contains the boundary values
Note
If the number of node equals 1, then the system is either discrete event system or a ternimal node of a hybrid system. For this type of system, the problem is actually not a trajectory optimization problem. Hence no need to enforce the collocation constraint and dynamics constraint.

◆ configureVariables()

function obj = TrajectoryOptimization.configureVariables ( struct  bounds)

This function configures the structure of the optimization variable by adding (registering) them to the optimization variable table.

A particular project might inherit the class and overload this function to achieve custom configuration of the optimization variables

Parameters
boundsa structed data stores the boundary information of the NLP variables
Required fields of bounds:

◆ directCollocation()

function fcstr = TrajectoryOptimization.directCollocation ( char  name,
SymVariable  x,
SymVariable  dx 
)

Return the SymFunction object of the direct collocation constraint given the state (x) and derivatives (dx).

Parameters
namethe name suffix of the function
xthe state SymVariable
dxthe derivative of states

◆ exportSolution()

function [ rowvec tspan , struct states , struct inputs , struct params ] = TrajectoryOptimization.exportSolution ( colvec  sol,
double  t0 
)

Analyzes the solution of the NLP problem.

Parameters
solThe solution vector of the NLP problem
t0the initial time
Return values
tspanthe time span of the trajectory
statesthe state trajectories
inputsthe input variable trajectories
paramsthe parameter variables

◆ removeConstraint()

function obj = TrajectoryOptimization.removeConstraint ( char  label)

Removes a group of NLP constraints.

See also
addConstraint
Parameters
labelthe label name (column) of the constraints

◆ removeCost()

function obj = TrajectoryOptimization.removeCost (   label)

Removes a group of NLP cost functions.

See also
addCost
Parameters
labelthe label name (column) of the cost function

◆ removeVariable()

function obj = TrajectoryOptimization.removeVariable ( char  label)

Removes a NLP optimization variable.

See also
addVariable
Parameters
labelthe label name (column) of the variable

◆ update()

function obj = TrajectoryOptimization.update ( )

Updates the NLP problems before load it to NLP solver.

Note
Overload the superclass (NonlinearProgram) for additional updates
Generated fields of obj:

◆ updateConstrProp()

function obj = TrajectoryOptimization.updateConstrProp ( char  label,
char  node,
  varargin 
)

This function updates the properties of the constraint objects based on the input name-value pair arguments.

Note
The note identifier can be either the numbers of node indices
or the following string to specify particular nodes
  • first: the first node
  • last: the last node
  • all: all nodes
  • cardinal: all cardinal (odd) nodes, only effective if HermiteSimpson scheme is used
  • interior: all interior (even) nodes, only effective if HermiteSimpson scheme is used
Parameters
labelthe row name of the constraints
nodethe identifier of the node list
vararginvariable nama-value pair input arguments, in detail:
updateConstrProp ( ..., lb, ub )
Required Parameters for varargin:
  • lb lower limit
  • ub upper limit

◆ updateCostProp()

function obj = TrajectoryOptimization.updateCostProp ( char  label,
char  node,
  varargin 
)

This function updates the properties of the cost function objects based on the input name-value pair arguments.

Note
The note identifier can be either the numbers of node indices
or the following string to specify particular nodes
  • first: the first node
  • last: the last node
  • all: all nodes
  • cardinal: all cardinal (odd) nodes, only effective if HermiteSimpson scheme is used
  • interior: all interior (even) nodes, only effective if HermiteSimpson scheme is used
Parameters
labelthe row name of the constraints
nodethe identifier of the node list
vararginvariable nama-value pair input arguments, in detail:
updateCostProp ( ..., lb, ub )
Required Parameters for varargin:
  • lb lower limit
  • ub upper limit

◆ updateVariableBounds()

function obj = TrajectoryOptimization.updateVariableBounds (   bounds)

This function updates the boundary conditions of the optimization variable by updating corresponding NLP variables.

Parameters
boundsa structed data stores the boundary information of the NLP variables
Required fields of bounds:

◆ updateVariableProp()

function obj = TrajectoryOptimization.updateVariableProp ( char  label,
char  node,
  varargin 
)

This function updates the properties of the NLP variable objects based on the input name-value pair arguments.

Note
The note identifier can be either the numbers of node indices
or the following string to specify particular nodes
  • first: the first node
  • last: the last node
  • all: all nodes
  • cardinal: all cardinal (odd) nodes, only effective if HermiteSimpson scheme is used
  • interior: all interior (even) nodes, only effective if HermiteSimpson scheme is used
Parameters
labelthe row name of the constraints
nodethe identifier of the node list
vararginvariable nama-value pair input arguments, in detail:
updateVariableProp ( ..., lb, ub, x0 )
Required Parameters for varargin:
  • lb lower limit
  • ub upper limit
  • x0 a typical value of the variable

Member Data Documentation

◆ ConstrTable

TrajectoryOptimization.ConstrTable

A table of NLP constraints. The row determines the identity of the constraint, and the column determines at which node the constraint is defined.

Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ CostTable

TrajectoryOptimization.CostTable

A table of cost functions. The row determines the identity of the function, and the column determines at which node the variable is defined.

Attention
We assume the cost functioin (or objective) of a NLP is the sum of these cost functions.
Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ DefaultNumberOfGrid

TrajectoryOptimization.DefaultNumberOfGrid = 10
static

The default number of collocation grids.

Note
This property has the MATLAB attribute Hidden set to true.
Matlab documentation of property attributes.
Default: 10

◆ NumNode

TrajectoryOptimization.NumNode

The number of discrete nodes along the trajectory.

Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ OptVarTable

TrajectoryOptimization.OptVarTable

A table of NLP decision variables. The row determines the identity of the variable, and the column determines at which node the variable is defined.

Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

◆ Plant

TrajectoryOptimization.Plant

The dynamical system plant of the interest.

Note
This property has non-standard access specifiers: SetAccess = Protected, GetAccess = Public
Matlab documentation of property attributes.

The documentation for this class was generated from the following files:
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/TrajectoryOptimization.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addCollocationConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addCost.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addDynamicsConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addInputVariable.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addNodeConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addNodeCost.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addParamVariable.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addRunningCost.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addStateVariable.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addTimeVariable.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/addVariable.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/checkConstraints.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/checkCosts.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/checkVariables.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/compileConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/compileObjective.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/configure.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/configureVariables.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/directCollocation.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/exportSolution.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/removeConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/removeCost.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/removeVariable.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/update.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/updateConstrProp.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/updateCostProp.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/updateVariableBounds.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@TrajectoryOptimization/updateVariableProp.m