RigidImpact represents a rigid body impact map assuming that the impact is plastic and occurs instantaneously. More...

Inheritance diagram for RigidImpact:
[legend]

Public Member Functions

 RigidImpact (char name,RigidLinks model,char event)
 the class constructin method More...
 
function obj = configure (char load_path)
 configure the reset map expression for the rigid impact object More...
 
function obj = addImpactConstraint (HolonomicConstraint constr, load_path)
 Adds an impact constraint to the rigid impact map. More...
 
function obj = removeImpactConstraint (cellstr name)
 Remove impact (holonomic) constraints defined for the system. More...
 
function TrajectoryOptimization nlp = rigidImpactConstraint (TrajectoryOptimization nlp,TrajectoryOptimization src,TrajectoryOptimization tar,struct bounds,varargin varargin)
 Impose system specific constraints as NLP constraints for the trajectory optimization problem. More...
 
function [ tn , xn , lambda ] = calcDiscreteMap (t,colvec x, varargin)
 calculates the discrete map of the dynamical system that maps xminus from xplus. Subclasses must implement this method by its own. More...
 
function obj = compile (char export_path,varargin varargin)
 export the symbolic expressions of the system dynamics matrices and vectors and compile as MEX files. More...
 
function obj = saveExpression (char export_path,varargin varargin)
 export the symbolic expressions of the system dynamics matrices and vectors and compile as MEX files. More...
 
- Public Member Functions inherited from DiscreteDynamics
 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

matrix R
 The coordinate relabeling matrix. More...
 
HolonomicConstraint ImpactConstraints
 The impact constraints (holonomic) More...
 
- Public Attributes inherited from DiscreteDynamics
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

RigidImpact represents a rigid body impact map assuming that the impact is plastic and occurs instantaneously.

Constructor & Destructor Documentation

◆ RigidImpact()

RigidImpact.RigidImpact ( char  name,
RigidLinks  model,
char  event 
)
inline

the class constructin method

Parameters
namethe name of the rigid impact dynamics
modelthe RigidLinks model object
eventthe event name of the rigid impact
Required fields of model:

Member Function Documentation

◆ addImpactConstraint()

function obj = RigidImpact.addImpactConstraint ( HolonomicConstraint  constr,
  load_path 
)
inline

Adds an impact constraint to the rigid impact map.

Parameters
constrthe expression of the constraints

◆ calcDiscreteMap()

function [ double tn , colvec xn , struct lambda ] = RigidImpact.calcDiscreteMap (   t,
colvec  x,
  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
tthe time instant
xthe pre-impact states
Return values
tnthe time after reset
xnthe post-impact states
lambdathe impulsive wrench

◆ compile()

function obj = RigidImpact.compile ( char  export_path,
varargin  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, File, ForceExport, BuildMex, Namespace )
Required Parameters for varargin:
  • StackVariable whether to stack variables into one
  • File the (full) file name of exported file
  • ForceExport force the export
  • BuildMex flag whether to MEX the exported file
  • Namespace the namespace of the function

◆ configure()

function obj = RigidImpact.configure ( char  load_path)
inline

configure the reset map expression for the rigid impact object

Parameters
load_paththe path from which the symbolic experssion can be load
Generated fields of obj:

◆ removeImpactConstraint()

function obj = RigidImpact.removeImpactConstraint ( cellstr  name)
inline

Remove impact (holonomic) constraints defined for the system.

Parameters
namethe name of the constraint
Generated fields of obj:

◆ rigidImpactConstraint()

function TrajectoryOptimization nlp = RigidImpact.rigidImpactConstraint ( TrajectoryOptimization  nlp,
TrajectoryOptimization  src,
TrajectoryOptimization  tar,
struct  bounds,
varargin  varargin 
)

Impose system specific constraints as NLP constraints for the trajectory optimization problem.

Parameters
nlpan trajectory optimization NLP object of the system
srcthe NLP of the source domain system
tarthe NLP of the target domain system
boundsa struct data contains the boundary values
vararginextra argument

◆ saveExpression()

function obj = RigidImpact.saveExpression ( char  export_path,
varargin  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
saveExpression ( ..., ForceExport )
Required Parameters for varargin:
  • ForceExport force the export

Member Data Documentation

◆ ImpactConstraints

RigidImpact.ImpactConstraints

The impact constraints (holonomic)

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

◆ R

RigidImpact.R

The coordinate relabeling matrix.

Note
This property has custom functionality when its value is changed.

The documentation for this class was generated from the following files:
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidImpact/RigidImpact.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidImpact/calcDiscreteMap.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidImpact/compile.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidImpact/rigidImpactConstraint.m
  • /home/ayonga/.dropboxes/business/Dropbox/research/dzopt/frost/matlab/robotics/@RigidImpact/saveExpression.m