Continuous state dynamic system governed by differential equations. More...

Inheritance diagram for ContinuousDynamics:
[legend]

Public Member Functions

 ContinuousDynamics (char type,char name)
 The class construction function. More...
 
function obj = addState (SymVariable x,SymVariable dx,SymVariable ddx)
 overload the superclass addState method with fixed state fields More...
 
function sol = simulate (t0, x0, tf, controller, params, logger, eventnames, options, solver)
 Simulate the dynamical system. More...
 
function [ value , isterminal , direction ] = checkGuard (t, x, controller, params, eventfuncs)
 Detect the guard condition (event trigger) More...
 
function obj = setMassMatrix (M)
 Set the mass matrix M(x) of the system. More...
 
function obj = setDriftVector (vf)
 Set the drift vector field Fvec(x) or Fvec(x,dx) of the system. More...
 
function obj = appendDriftVector (vf)
 Append additional vf to the drift vector field Fvec(x) or Fvec(x,dx) of the system. More...
 
function M = calcMassMatrix (x)
 calculates the mass matrix Mmat(x) More...
 
function f = calcDriftVector (x, dx)
 calculates the mass matrix Fvec(x) or Fvec(x,dx) More...
 
function [ xdot , extra ] = calcDynamics (t, x, controller, params, logger)
 calculate the dynamical equation dx More...
 
function [ xdot , extra ] = firstOrderDynamics (t, x, controller, params, logger)
 calculate the dynamical equation of the first order dynamical system More...
 
function [ xdot , extra ] = secondOrderDynamics (t, x, controller, params, logger)
 calculate the dynamical equation of the second order dynamical system 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 = addEvent (constr)
 Adds event function for the dynamical system states and inputs. More...
 
function obj = removeEvent (name)
 Remove event functions defined for the system. More...
 
function obj = addHolonomicConstraint (constr, load_path)
 Adds a holonomic constraint to the dynamical system. More...
 
function obj = removeHolonomicConstraint (name)
 Remove holonomic constraints defined for the system. More...
 
function obj = addUnilateralConstraint (constr)
 Adds unilateral (inequality) constraints on the dynamical system states and inputs. More...
 
function obj = removeUnilateralConstraint (name)
 Remove unilateral constraints defined for the system. More...
 
function obj = addVirtualConstraint (constr)
 Adds a set of virtual constraints to the dynamical system. More...
 
function obj = removeVirtualConstraint (name)
 Remove virtual constraints defined for the system. More...
 
function obj = saveExpression (export_path, varargin)
 save the symbolic expression of system dynamical equations to a MX binary files More...
 
function obj = loadDynamics (file_path, vf_names, skip_load_vf)
 load the symbolic expression of system dynamical equations from MX binary files for fast loading More...
 
function obj = clearKernel (varargin)
 
- 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 PreProcess
 pre-process function handle of the object before the simulation More...
 
function_handle PostProcess
 pre-process function handle of the object after the simulation More...
 
function_handle UserNlpConstraint
 A handle to a function called by a trajectory optimization NLP to enforce system specific constraints. More...
 
struct Flow
 The flow (trajectory) from the dynamical system simulation. More...
 
SymFunction Mmat
 The mass matrix Mmat(x) More...
 
cell Fvec
 The cell array of the drift vector fields Fvec(x) SymFunction. More...
 
struct HolonomicConstraints
 The holonomic constraints of the dynamical system. More...
 
struct UnilateralConstraints
 The unilateral constraints of the dynamical system. More...
 
struct VirtualConstraints
 The virtual constraints of the dynamical system. More...
 
struct EventFuncs
 The event functions. More...
 
SymFunction MmatDx
 The left hand side of the dynamical equation: M(x)dx or M(x)ddx. 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

Continuous state dynamic system governed by differential equations.

It could be either a

first order system with the form

\begin{eqnarray*} Mmat(x)\dot{x}= Fvec(x) + Gvec(x,u) \end{eqnarray*}

or a second order system with the form

\begin{eqnarray*} Mmat(x)\ddot{x}= Fvec(x,\dot{x}) + Gvec(x,u) \end{eqnarray*}

Further, if the inputs (u) are affine, the system can be written as

either for first order system of the form

\begin{eqnarray*} Mmat(x)\dot{x}= Fvec(x) + Gmap(x) u \end{eqnarray*}

or a second order system of the form

\begin{eqnarray*} Mmat(x)\ddot{x}= Fvec(x,\dot{x}) + Gmap(x) u \end{eqnarray*}

Author
ayonga
Date
2017-02-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

◆ ContinuousDynamics()

ContinuousDynamics.ContinuousDynamics ( char  type,
char  name 
)
inline

The class construction function.

Parameters
typethe type of the system
namethe name of the system

Member Function Documentation

◆ addEvent()

function obj = ContinuousDynamics.addEvent (   constr)

Adds event function for the dynamical system states and inputs.

Parameters
constrthe event function

◆ addHolonomicConstraint()

function obj = ContinuousDynamics.addHolonomicConstraint (   constr,
  load_path 
)

Adds a holonomic constraint to the dynamical system.

Note
Any holonomic constraint introduces a set of constrained wrenchs to the system (Lagrangian multiplier).
Parameters
constrthe expression of the constraints
load_paththe path from which the symbolic expressions for the input map can be loaded

◆ addState()

function obj = ContinuousDynamics.addState ( SymVariable  x,
SymVariable  dx,
SymVariable  ddx 
)
inline

overload the superclass addState method with fixed state fields

Parameters
xthe state variables
dxthe first order derivative of state variables
ddxthe second order derivative of state variables

◆ addUnilateralConstraint()

function obj = ContinuousDynamics.addUnilateralConstraint (   constr)

Adds unilateral (inequality) constraints on the dynamical system states and inputs.

Parameters
constrthe unilateral constraints

◆ addVirtualConstraint()

function obj = ContinuousDynamics.addVirtualConstraint (   constr)

Adds a set of virtual constraints to the dynamical system.

Parameters
constrthe VirtualConstraint object

◆ appendDriftVector()

function obj = ContinuousDynamics.appendDriftVector (   vf)

Append additional vf to the drift vector field Fvec(x) or Fvec(x,dx) of the system.

Parameters
vfthe f(x)
Generated fields of obj:

◆ calcDriftVector()

function f = ContinuousDynamics.calcDriftVector (   x,
  dx 
)

calculates the mass matrix Fvec(x) or Fvec(x,dx)

Parameters
xthe state variables
dxthe first order derivative of state variables
Todo:
This calculation is slow due to multiple function invoke. Better ideas to improve the speed?

◆ calcDynamics()

function colvec xdot = ContinuousDynamics.calcDynamics (   t,
  x,
  controller,
  params,
  logger 
)

calculate the dynamical equation dx

Parameters
tthe time instant
xthe states
controllerthe controller
paramsthe parameter structure
loggerthe data logger object
Return values
xdotthe derivative of the system states

◆ calcMassMatrix()

function M = ContinuousDynamics.calcMassMatrix (   x)

calculates the mass matrix Mmat(x)

Parameters
xthe state variables

◆ checkGuard()

function [ value , isterminal , direction ] = ContinuousDynamics.checkGuard (   t,
  x,
  controller,
  params,
  eventfuncs 
)

Detect the guard condition (event trigger)

Parameters
tthe absolute time
xthe system states
controllerthe controller
paramsthe parameter structure
eventfuncsa list of event function
Required fields of eventfuncs:

◆ clearKernel()

function obj = ContinuousDynamics.clearKernel (   varargin)

◆ compile()

function obj = ContinuousDynamics.compile (   export_path,
  varargin 
)

export the symbolic expressions of the system dynamics matrices and vectors and compile as MEX files.

Parameters
export_paththe path to export the file
vararginvariable input parameters
compile ( ..., StackVariable, ForceExport, BuildMex, Namespace, NoPrompt )
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
  • NoPrompt answer yes to all prompts

◆ firstOrderDynamics()

function colvec xdot = ContinuousDynamics.firstOrderDynamics (   t,
  x,
  controller,
  params,
  logger 
)

calculate the dynamical equation of the first order dynamical system

Parameters
tthe time instant
xthe states
controllerthe controller
paramsthe parameter structure
loggerthe data logger object
Return values
xdotthe derivative of the system states
Required fields of logger:

◆ loadDynamics()

function obj = ContinuousDynamics.loadDynamics (   file_path,
  vf_names,
  skip_load_vf 
)

load the symbolic expression of system dynamical equations from MX binary files for fast loading

Parameters
file_paththe path to the files
vf_namesthe names of the drift vectors Fvec
skip_load_vfindicates whether to skip the loading of drift vectors which could takes a long time
Generated fields of obj:

◆ removeEvent()

function obj = ContinuousDynamics.removeEvent (   name)

Remove event functions defined for the system.

Parameters
namethe name of the constraint
Generated fields of obj:

◆ removeHolonomicConstraint()

function obj = ContinuousDynamics.removeHolonomicConstraint (   name)

Remove holonomic constraints defined for the system.

Parameters
namethe name of the constraint
Generated fields of obj:

◆ removeUnilateralConstraint()

function obj = ContinuousDynamics.removeUnilateralConstraint (   name)

Remove unilateral constraints defined for the system.

Parameters
namethe name of the constraint
Generated fields of obj:

◆ removeVirtualConstraint()

function obj = ContinuousDynamics.removeVirtualConstraint (   name)

Remove virtual constraints defined for the system.

Parameters
namethe name of the constraint
Generated fields of obj:

◆ saveExpression()

function obj = ContinuousDynamics.saveExpression (   export_path,
  varargin 
)

save the symbolic expression of system dynamical equations to a MX binary files

Parameters
export_paththe path to export the file
vararginvariable input parameters
saveExpression ( ..., ForceExport )
Required Parameters for varargin:
  • ForceExport force the export

◆ secondOrderDynamics()

function colvec xdot = ContinuousDynamics.secondOrderDynamics (   t,
  x,
  controller,
  params,
  logger 
)

calculate the dynamical equation of the second order dynamical system

Parameters
tthe time instant
xthe states
controllerthe controller
paramsthe parameter structure
loggerthe data logger object
Return values
xdotthe derivative of the system states
Required fields of logger:

◆ setDriftVector()

function obj = ContinuousDynamics.setDriftVector (   vf)

Set the drift vector field Fvec(x) or Fvec(x,dx) of the system.

Parameters
vfthe f(x)
Generated fields of obj:

◆ setMassMatrix()

function obj = ContinuousDynamics.setMassMatrix (   M)

Set the mass matrix M(x) of the system.

Parameters
Mthe mass matrix M(x)
Required fields of M:
Generated fields of obj:

◆ simulate()

function [ struct sol , struct params ] = ContinuousDynamics.simulate (   t0,
  x0,
  tf,
  controller,
  params,
  logger,
  eventnames,
  options,
  solver 
)

Simulate the dynamical system.

Parameters
t0the starting time instant
x0the initial states
tfthe terminating time instant
controllerthe controller for the dynamical system
paramsextra parameters
loggerthe data logger object
eventnamesthe name of eventnames to be used
optionssimulation options of hybrid system
solverthe ODE solver
Return values
sola structure contains the integration result of the ODE solver
Required fields of logger:

References outputfcn(), and str_index().

Member Data Documentation

◆ EventFuncs

ContinuousDynamics.EventFuncs

The event functions.

The event functions are often subset of the unilateral constraints defined on the system. For flexibility, we define them separately.

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

◆ Flow

ContinuousDynamics.Flow

The flow (trajectory) from the dynamical system simulation.

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

◆ Fvec

ContinuousDynamics.Fvec

The cell array of the drift vector fields Fvec(x) SymFunction.

We split the Fvec into many sub-vectors Fvec[i], such that

\begin{eqnarray*} Fvec = \sum_i^N Fvec[i] \end{eqnarray*}

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

◆ HolonomicConstraints

ContinuousDynamics.HolonomicConstraints

The holonomic constraints of the dynamical system.

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

◆ Mmat

ContinuousDynamics.Mmat

The mass matrix Mmat(x)

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

◆ MmatDx

ContinuousDynamics.MmatDx

The left hand side of the dynamical equation: M(x)dx or M(x)ddx.

Note
This property has the MATLAB attribute Hidden set to true.
This property has non-standard access specifiers: SetAccess = Private, GetAccess = Public
Matlab documentation of property attributes.

◆ PostProcess

ContinuousDynamics.PostProcess

pre-process function handle of the object after the simulation

The function handle should have the syntax
params = postPorcess(sys, sol, controller, params, varargin)

◆ PreProcess

ContinuousDynamics.PreProcess

pre-process function handle of the object before the simulation

The function handle should have the syntax
params = preProcess(sys, t, x, controller, params, varargin)

◆ UnilateralConstraints

ContinuousDynamics.UnilateralConstraints

The unilateral constraints of the dynamical system.

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

◆ UserNlpConstraint

ContinuousDynamics.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(nlp, bounds, varargin)

◆ VirtualConstraints

ContinuousDynamics.VirtualConstraints

The virtual constraints of the dynamical system.

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/system/@ContinuousDynamics/ContinuousDynamics.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/addEvent.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/addHolonomicConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/addUnilateralConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/addVirtualConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/appendDriftVector.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/calcDriftVector.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/calcDynamics.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/calcMassMatrix.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/checkGuard.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/compile.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/firstOrderDynamics.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/loadDynamics.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/removeEvent.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/removeHolonomicConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/removeUnilateralConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/removeVirtualConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/saveExpression.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/secondOrderDynamics.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/setDriftVector.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/setMassMatrix.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/system/@ContinuousDynamics/simulate.m