Discrete event dynamic system governed by discrete transition map and triggered by discrete events. More...
Public Member Functions | |
| DiscreteDynamics (char type,char name,char event) | |
| the constructor function for DiscreteDynamics class objects More... | |
| function obj = | addState (SymVariable x,SymVariable xn,SymVariable dx,SymVariable dxn) |
overload the superclass addState method with fixed state fields More... | |
| function [ tn , xn ] = | calcDiscreteMap (double t,colvec x,varargin varargin) |
| calculates the discrete map of the dynamical system that maps xminus from xplus. Subclasses must implement this method by its own. More... | |
| function TrajectoryOptimization nlp = | IdentityMapConstraint (TrajectoryOptimization nlp,TrajectoryOptimization src,TrajectoryOptimization tar,struct bounds,varargin varargin) |
| Impose system specific constraints as NLP constraints for the trajectory optimization problem. More... | |
Public Member Functions inherited from DynamicalSystem | |
| function obj = | addState (varargin) |
| Add state variables of the dynamical system. More... | |
| function obj = | addInput (category, name, var, gf, varargin) |
| Add input variables of the dynamical system. More... | |
| function obj = | removeInput (category, name) |
| Remove input variables of the dynamical system. More... | |
| function obj = | addParam (varargin) |
| Add parameter variables of the dynamical system. More... | |
| function obj = | removeParam (param_name) |
| Remove parameter variables of the dynamical system. More... | |
| function obj = | setParamValue (varargin) |
| set the actual value of the system parameters More... | |
| function obj = | compile (export_path, varargin) |
| export the symbolic expressions of the system dynamics matrices and vectors and compile as MEX files. More... | |
| function obj = | loadDynamics (export_path, varargin) |
| function obj = | saveExpression (export_path, varargin) |
| save the symbolic expression of system dynamical equations to a MX binary files More... | |
| DynamicalSystem (char type,char name) | |
| The class construction function. More... | |
| function obj = | setName (name) |
| set the name of the dynamical system More... | |
| function ret = | isParam (char name) |
| function var_group = | validateVarName (char name) |
Validate the group and category of the variables specified by the input name More... | |
| function obj = | setType (char type) |
| Sets the type of the dynamical system. More... | |
Public Attributes | |
| function_handle | UserNlpConstraint |
| A handle to a function called by a trajectory optimization NLP to enforce system specific constraints. More... | |
| char | EventName |
| The event name that triggers the discrete dynamics. More... | |
Public Attributes inherited from DynamicalSystem | |
| char | Name |
| The unique name identification of the system. More... | |
| function_handle | ExternalInputFun |
| Returns the external input defined on the dynamical system. More... | |
| char | Type |
| The highest order of the state derivatives of the system. More... | |
| struct | States |
| A structure that contains the symbolic representation of state variables. More... | |
| double | numState |
| The total number of system states. More... | |
| struct | Inputs |
| A structure that contains the symbolic representation of input variables. More... | |
| struct | Params |
| The parameters of the system. More... | |
| struct | Gvec |
| The struct of input vector fields Gvec(x,u) SymFunction. More... | |
| struct | Gmap |
| The struct of input map Gmap(x) SymFunction. 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... | |
Additional Inherited Members | |
Protected Member Functions inherited from DynamicalSystem | |
| function value = | getValue (vars) |
| returns the variables (vars) value that are stored during computing the dynamics More... | |
| function v_type = | validateSystemType (type) |
| validate if it is valid system type More... | |
Protected Attributes inherited from DynamicalSystem | |
| double | t_ |
| The time. More... | |
| struct | states_ |
| The states. More... | |
| struct | inputs_ |
| The inputs. More... | |
| struct | params_ |
| The parameters. More... | |
| struct | GmapName_ |
| The name of the Gmap functions. More... | |
| struct | GvecName_ |
| The name of the Gvec functions. More... | |
Detailed Description
Discrete event dynamic system governed by discrete transition map and triggered by discrete events.
- Date
- 2017-04-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
◆ DiscreteDynamics()
the constructor function for DiscreteDynamics class objects
- Parameters
-
type the type of the system name the name of the system event the event name associated with the discrete map
Member Function Documentation
◆ addState()
|
inline |
overload the superclass addState method with fixed state fields
- Parameters
-
x the pre-impact state variables xn the post-impact state variables dx the pre-impact first order derivative of state variables dxn the post-impact first order derivative of state variables
◆ calcDiscreteMap()
| function [ double tn , colvec xn ] = DiscreteDynamics.calcDiscreteMap | ( | double | t, |
| colvec | x, | ||
| varargin | varargin | ||
| ) |
calculates the discrete map of the dynamical system that maps xminus from xplus. Subclasses must implement this method by its own.
- Note
- By default, this discrete map will be a Identity map. For specific discrete map, please implement as a subclass of this class
- Parameters
-
t the time instant x the pre-impact states varargin extra argument
- Return values
-
tn the time after reset xn the post-impact states
◆ IdentityMapConstraint()
| function TrajectoryOptimization nlp = DiscreteDynamics.IdentityMapConstraint | ( | TrajectoryOptimization | nlp, |
| TrajectoryOptimization | src, | ||
| TrajectoryOptimization | tar, | ||
| struct | bounds, | ||
| varargin | varargin | ||
| ) |
Impose system specific constraints as NLP constraints for the trajectory optimization problem.
- Parameters
-
nlp an trajectory optimization NLP object of the system src the NLP of the source domain system tar the NLP of the target domain system bounds a struct data contains the boundary values varargin extra arguments
Member Data Documentation
◆ EventName
| DiscreteDynamics.EventName |
The event name that triggers the discrete dynamics.
- Note
- This property has custom functionality when its value is changed.
◆ UserNlpConstraint
| DiscreteDynamics.UserNlpConstraint |
A handle to a function called by a trajectory optimization NLP to enforce system specific constraints.
- The function handle should have the syntax
- userNlpConstraint(edge_nlp, src_nlp, tar_nlp, bounds, varargin)
The documentation for this class was generated from the following files:
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@DiscreteDynamics/DiscreteDynamics.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@DiscreteDynamics/calcDiscreteMap.m
- /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@DiscreteDynamics/IdentityMapConstraint.m
Public Member Functions inherited from