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

class genericPath

A base class for cartesian-space trajectories.

Inheritance:


Public Fields

[more]int pathNum
the group of paths to which the path belongs.
[more]int endPtNum
the index of the end effector that should follow the path
[more]int reachedStart
indicates whether the robot has reached the first point on the the path yet
[more]int reachedEnd
indicates whether the robot has reached the last point on the the path yet
[more]int usePayload
indicates whether a payload should be moved along the path
[more]payload* pl
the payload (if any) being moved along the path
[more]int useAppliedForce
indicates whether the end effector should apply a force and and torque as it moves along the path
[more]triple toolForce
the force (if useAppliedForce is 1) to apply along the path
[more]triple toolTorque
the torque (if useAppliedForce is 1) to apply along the path
[more]endPointRec* endPt
a pointer to the end effector (if any) currently following the path
[more]const char* payloadLabel
the label for the payload (if any) to be moved along the path
[more]int payloadConnectorID
the ID of the connector on the payload that should be connected to the tool's TCP
[more]int alignPayload
indicates whether the payload's connector should be aligned to the tool's TCP before attaching it.

Public Methods

[more] ~genericPath(void)
destructor
[more]virtual void getStartPoint(triple &t, quaternion &q) = 0
returns the pose of the first point on the path
[more]virtual vector computeVel(double dt, quaternion* outputFrame = NULL) = 0
computes a velocity command for the end effector.
[more]virtual void reset(void)
resets the path state
[more]virtual int atStart(void)
returns 1 if the end effector has reached the first point on the path
[more]virtual int done(void)
returns 1 if the end effector has reached the last point on the path
[more]virtual double completion(void)
returns a number between 0 and 1 indicating the fraction of the the path that has been completed
[more]virtual triple computeCrossTrackError(triple &pos) = 0
returns the current cross-track error of the given position
[more]virtual triple computeOrientationError(quaternion &q) = 0
returns the current orientation error of the given orientation


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 readParams(paramParser* parser)
ovirtual int setVariables(const ptrList* taskParamRecs)
ovirtual int simInit(d2kSimulator* Sim)
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 base class for cartesian-space trajectories. File variables
oint pathNum
the group of paths to which the path belongs. This is used by the pathEvaluator to group paths together if they should be simultaneously followed by multiple end effectors

oint endPtNum
the index of the end effector that should follow the path

oint reachedStart
indicates whether the robot has reached the first point on the the path yet

oint reachedEnd
indicates whether the robot has reached the last point on the the path yet

oint usePayload
indicates whether a payload should be moved along the path

opayload* pl
the payload (if any) being moved along the path

oint useAppliedForce
indicates whether the end effector should apply a force and and torque as it moves along the path

otriple toolForce
the force (if useAppliedForce is 1) to apply along the path

otriple toolTorque
the torque (if useAppliedForce is 1) to apply along the path

oendPointRec* endPt
a pointer to the end effector (if any) currently following the path

oconst char* payloadLabel
the label for the payload (if any) to be moved along the path

oint payloadConnectorID
the ID of the connector on the payload that should be connected to the tool's TCP

oint alignPayload
indicates whether the payload's connector should be aligned to the tool's TCP before attaching it.

o ~genericPath(void)
destructor

ovirtual void getStartPoint(triple &t, quaternion &q) = 0
returns the pose of the first point on the path

ovirtual vector computeVel(double dt, quaternion* outputFrame = NULL) = 0
computes a velocity command for the end effector. If outputFrame is non-NULL, then the velocity will be transformed by it.

ovirtual void reset(void)
resets the path state

ovirtual int atStart(void)
returns 1 if the end effector has reached the first point on the path

ovirtual int done(void)
returns 1 if the end effector has reached the last point on the path

ovirtual double completion(void)
returns a number between 0 and 1 indicating the fraction of the the path that has been completed

ovirtual triple computeCrossTrackError(triple &pos) = 0
returns the current cross-track error of the given position

ovirtual triple computeOrientationError(quaternion &q) = 0
returns the current orientation error of the given orientation


Direct child classes:
path

Alphabetic index HTML hierarchy of classes or Java



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