HybridTrajectoryOptimization defines a particular type of nonlinear programing problem — trajectory optimization problem for a hybrid dynamical system. More...
Public Member Functions | |
HybridTrajectoryOptimization (char name,HybridSystem plant,integerConstantTimeHorizon num_grid,struct bounds, varargin) | |
The constructor function. More... | |
function obj = | addJumpConstraint (TrajectoryOptimization edge,TrajectoryOptimization src,TrajectoryOptimization tar,struct bounds,varargin varargin) |
Add jump constraints between the edge and neighboring two nodes (source and target) More... | |
function | validateGraph (plant) |
validate the directed graph of the hybrid system model More... | |
function obj = | configure (struct bounds, varargin) |
configure the trajectory optimizatino NLP problem More... | |
function obj = | updateVariableBounds (struct bounds) |
This function updates the boundary conditions of the optimization variable by updating corresponding NLP variables. More... | |
function obj = | update () |
Updates the NLP problems before load it to NLP solver. More... | |
function phase_idx = | getPhaseIndex (varargin) |
Returns the index of a particular phase (TrajectoryOptimization object) associated with the input argument. More... | |
function [ yc , cl , cu ] = | checkConstraints (x, tol, output_file) |
Check the violation of the constraints. More... | |
function yc = | checkCosts (x, output_file) |
Check the value of const function. More... | |
function | checkVariables (x, tol, output_file) |
Check the violation of the constraints. More... | |
function [ tspan , states , inputs , params ] = | exportSolution (colvec sol) |
Analyzes the solution of the NLP problem. More... | |
function | compileConstraint (integer phase,cellstr constr,char export_path,cellstr exclude,varargin varargin) |
Compile and export symbolic expression and derivatives of all NLP functions. More... | |
function | compileObjective (integer phase,cellstr cost,char export_path,cellstr exclude,varargin varargin) |
Compile and export symbolic expression and derivatives of all NLP functions. 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 | |
TrajectoryOptimization | Phase |
The discrete phases of the hybrid trajectory optimization. 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... | |
Detailed Description
HybridTrajectoryOptimization defines a particular type of nonlinear programing problem — trajectory optimization problem for a hybrid dynamical system.
Constructor & Destructor Documentation
◆ HybridTrajectoryOptimization()
|
inline |
The constructor function.
- Parameters
-
name the name of the NLP plant the hybrid system plant num_grid the number of grids along the trajectory bounds a structed data stores the boundary information of the NLP variables varargin
Member Function Documentation
◆ addJumpConstraint()
function obj = HybridTrajectoryOptimization.addJumpConstraint | ( | TrajectoryOptimization | edge, |
TrajectoryOptimization | src, | ||
TrajectoryOptimization | tar, | ||
struct | bounds, | ||
varargin | varargin | ||
) |
Add jump constraints between the edge and neighboring two nodes (source and target)
These constraints include the continuity of the states/time variables, as well as system-specific discrete map constraint of the guard dynamics, and user-specific constraints.
- Parameters
-
edge the edge NLP src the source node NLP tar the target node NLP bounds the boundary values varargin extra argument
- Required fields of src:
- Required fields of tar:
- Required fields of edge:
◆ checkConstraints()
function [ yc , cl , cu ] = HybridTrajectoryOptimization.checkConstraints | ( | x, | |
tol, | |||
output_file | |||
) |
Check the violation of the constraints.
◆ checkCosts()
function yc = HybridTrajectoryOptimization.checkCosts | ( | x, | |
output_file | |||
) |
Check the value of const function.
◆ checkVariables()
function HybridTrajectoryOptimization.checkVariables | ( | x, | |
tol, | |||
output_file | |||
) |
Check the violation of the constraints.
◆ compileConstraint()
function HybridTrajectoryOptimization.compileConstraint | ( | integer | phase, |
cellstr | constr, | ||
char | export_path, | ||
cellstr | exclude, | ||
varargin | varargin | ||
) |
Compile and export symbolic expression and derivatives of all NLP functions.
- Note
- If
phase
is empty, then it will compile all phases. -
If
constr
is emtpy, then it will compile all constraints.
- Parameters
-
phase the phase Nlp constr a list of constraints to be compiled export_path the path to export the file exclude a list of functions to be excluded varargin variable input parameters Required Parameters for varargin:compileConstraint ( ..., StackVariable, ForceExport, BuildMex, Namespace )- 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 obj = HybridTrajectoryOptimization.compileObjective | ( | integer | phase, |
cellstr | cost, | ||
char | export_path, | ||
cellstr | exclude, | ||
varargin | varargin | ||
) |
Compile and export symbolic expression and derivatives of all NLP functions.
- Note
- If
phase
is empty, then it will compile all phases. -
If
cost
is emtpy, then it will compile all cost functions.
- Parameters
-
phase the phase Nlp cost a list of cost function to be compiled export_path the path to export the file exclude a list of functions to be excluded varargin variable input parameters Required Parameters for varargin:compileObjective ( ..., StackVariable, ForceExport, BuildMex, Namespace )- 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
◆ configure()
function obj = HybridTrajectoryOptimization.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
-
bounds a struct data contains the boundary values
◆ exportSolution()
function [ tspan , states , inputs , params ] = HybridTrajectoryOptimization.exportSolution | ( | colvec | sol | ) |
Analyzes the solution of the NLP problem.
- Parameters
-
sol The solution vector of the NLP problem
◆ getPhaseIndex()
function phase_idx = HybridTrajectoryOptimization.getPhaseIndex | ( | varargin | ) |
Returns the index of a particular phase (TrajectoryOptimization object) associated with the input argument.
The input argument can be the node name/index or the edge endnodes. If there is only one input argument, then it will returns the associated phase index of the node; if there are two input argument, then it will returns the associated phase index of the edge.
- For example
idx = getPhaseIndex(obj, nodeID)
will return the continuous phase;
idx = getPhaseIndex(obj, s, t)
will return the discrete phase.
◆ update()
function obj = HybridTrajectoryOptimization.update | ( | ) |
Updates the NLP problems before load it to NLP solver.
- Note
- Overload the superclass (NonlinearProgram) for additional updates
- Generated fields of obj:
◆ updateVariableBounds()
function obj = HybridTrajectoryOptimization.updateVariableBounds | ( | struct | bounds | ) |
This function updates the boundary conditions of the optimization variable by updating corresponding NLP variables.
- Parameters
-
bounds a structed data stores the boundary information of the NLP variables
◆ validateGraph()
function HybridTrajectoryOptimization.validateGraph | ( | plant | ) |
validate the directed graph of the hybrid system model
- Note
- The hybrid trajectory optimization problem is only able to handle system graph that is cyclic or with single branches.
- Required fields of plant:
Member Data Documentation
◆ Phase
HybridTrajectoryOptimization.Phase |
The discrete phases of the hybrid trajectory optimization.
The documentation for this class was generated from the following files:
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/HybridTrajectoryOptimization.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/addJumpConstraint.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/checkConstraints.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/checkCosts.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/checkVariables.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/compileConstraint.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/compileObjective.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/configure.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/exportSolution.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/getPhaseIndex.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/update.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/updateVariableBounds.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/nlp/@HybridTrajectoryOptimization/validateGraph.m