In file /home/blah/darwin2k/src/d2k/ctrl/sriController.h:

class sriController

a robot controller that uses the singularity robust inverse (SRI) of the jacobian to follow cartesian-space trajectories.

Inheritance:


Public Fields

[more] Internal controller state
[more]double mu
ratio for detecting singularity This variable's value must often be tuned for a specific configuration and task.
[more]double lambda0
weight for identity matrix in SRI This variable's value must often be tuned for a specific configuration and task.
[more]int singularCount
records the number of times the jacobian was singular
[more]double ignoreLimitThresh
threshold for joint limit avoidance.
[more]double gradientStepSize
size of step to take in gradient direction.
[more]int doGradientDescent
determines whether joint limits are avoided using a gradient descent method
[more]const char* jointControllerName
the label of the jointController (if any) to be used to compute torque commands from velocity commands
[more]double minRate
the minimum rate considered to be progress towards a goal
[more]int reachedFirst
indicates whether the first points of all paths have been reached
[more]int lastNumEndPts
indicates whether the last points of all paths have been reached
[more]sriControllerMode mode
the current controller mode
[more]jointController* jtCtrl
the joint controller used to compute torque commands (if any)

Public Methods

[more] sriController(void)
constructor
[more] ~sriController(void)
destructor
[more]virtual int readParams(paramParser* parser)
reads sriController-specific parameters from a p-file parser.
[more]virtual int setVariables(const ptrList* taskParams)
reads sriController-specific variables from task parameters.
[more]virtual int simInit(d2kSimulator* sim)
locates the jointController named by the variable jointControllerName, if any, and stores it in jtCtrl
[more]void setMode(sriControllerMode m)
sets the current mode

Public Members

[more]enum sriControllerMode
control modes for sriControllers.


Inherited from controller:

Public Fields

ovector accCmd
ovector Tcmd
omechanism* mech
odynoTimer* timer
odofInfluence* inf
oint alwaysUpdate

Public Methods

ovirtual double maxDt(void)
ovirtual int computeTorqueCommand(double currentTime, int &computedAcc)
ovirtual int computeAccelerationCommand(double currentTime)
ovirtual int madeProgress(double currentTime)
ovirtual int reset(void)

Public Members

o inherited from d2kComponent
o not currently used

Protected Fields

odouble _maxDt


Inherited from d2kComponent:

Public Fields

od2kSimulator* sim
oconfiguration* cfg
oconst char* label
oint active

Public Methods

ovirtual int minCfgs(void) const
ovirtual int maxCfgs(void) const
ovirtual const char* getCfgName(int i)
ovirtual int init(ptrList* Cfgs)
ovirtual int forceCfgResolution(void)
ovirtual int cleanup(void)
ovirtual int update(int &violated)
ovirtual const cfgLabelRecord* getLabelRec(int i) const


Inherited from synObject:

Public Fields

ostatic int staticClassID
oint objectID
oint verboseLevel

Public Methods

ovirtual const char* className(void) const
ovirtual synObject* copy(void) const
ovirtual int isOfType(int typeNum, int derivedOk)
ostatic int setStaticClassID(void)
ovirtual int classID(void) const


Documentation

a robot controller that uses the singularity robust inverse (SRI) of the jacobian to follow cartesian-space trajectories. This controller is based on the original SRI formulation (see work by Nakamura or by Kelmar & Khosla), with joint limit avoidance (see Leigois), and with several additions as described in the Darwin2K book (or thesis).

File variables

Also see controller class for other parameters.
oenum sriControllerMode
control modes for sriControllers.

o Internal controller state

ovector velCmd
the computed joint velocity command

ovector limitGradient
gradient of the configuration's joint limit function, used for joint limit avoidance if a robot has kinematic redundancy

ovector dx
desired cartesian motion vector for all end effectors

ovector cost
cost vector for all DOFs

ovector maxVel
maximum velocity vector for all DOFs

omatrix nullSpace
nullspace of cfg's jacobian, used for joint limit avoidance

omatrix nullSpaceInv
pseudoinverse of nullspace

omatrix P
projection matrix; projects onto nullspace

omatrix* dirP
projection matrix--removes unwanted components from jacobian & commands

odouble lastOmega
manipulability measure at previous timestep

odouble mu
ratio for detecting singularity This variable's value must often be tuned for a specific configuration and task. When synthesizing configurations, it is a good idea to include this as a task parameter.

odouble lambda0
weight for identity matrix in SRI This variable's value must often be tuned for a specific configuration and task. When synthesizing configurations, it is a good idea to include this as a task parameter.

oint singularCount
records the number of times the jacobian was singular

odouble ignoreLimitThresh
threshold for joint limit avoidance. Joint limit gradients with magnitudes less than ignoreLimitThresh are ignored. This variable's value must often be tuned for a specific configuration and task. When synthesizing configurations, it is a good idea to include this as a task parameter.

odouble gradientStepSize
size of step to take in gradient direction. This variable's value must often be tuned for a specific configuration and task. When synthesizing configurations, it is a good idea to include this as a task parameter.

oint doGradientDescent
determines whether joint limits are avoided using a gradient descent method

oconst char* jointControllerName
the label of the jointController (if any) to be used to compute torque commands from velocity commands

odouble minRate
the minimum rate considered to be progress towards a goal

oint reachedFirst
indicates whether the first points of all paths have been reached

oint lastNumEndPts
indicates whether the last points of all paths have been reached

osriControllerMode mode
the current controller mode

ojointController* jtCtrl
the joint controller used to compute torque commands (if any)

o sriController(void)
constructor

o ~sriController(void)
destructor

ovirtual int readParams(paramParser* parser)
reads sriController-specific parameters from a p-file parser. The variables read from the p-file are: See the documentation for each of these members for their meanings.

ovirtual int setVariables(const ptrList* taskParams)
reads sriController-specific variables from task parameters. The variables used are: See the documentation for each of these members for their meanings.

ovirtual int simInit(d2kSimulator* sim)
locates the jointController named by the variable jointControllerName, if any, and stores it in jtCtrl

ovoid setMode(sriControllerMode m)
sets the current mode


Direct child classes:
ffController

Alphabetic index HTML hierarchy of classes or Java



This page was generated with the help of DOC++.