Actin®  Version 5.1.0
Software for Robotics Simulation and Control
EcEndEffector Class Referenceabstract

Holds a base class for single end-effector components. More...

#include <ecEndEffector.h>

Inheritance diagram for EcEndEffector:
EcXmlCompoundType EcXmlObject EcCoordinatedJointEndEffector EcFrameBasedEndEffector EcPointBasedEndEffector EcPointRotateEndEffector EcRotationBasedEndEffector EcSagEndEffector EcScalarBasedEndEffector EcSewAngleEndEffector EcSpatialMomentumEndEffector

Public Types

enum  ControlMode {
  POSITION_CONTROL = 0,
  VELOCITY_CONTROL,
  PROFILED_POSITION
}
 
- Public Types inherited from EcXmlCompoundType
enum  {
  READONLYCOMPONENT = 0,
  READONLYATTRIBUTE
}
 special-descriptor codes More...
 

Public Member Functions

 EcEndEffector ()
 default constructor
 
virtual ~EcEndEffector ()
 destructor
 
 EcEndEffector (const EcEndEffector &orig)
 copy constructor
 
EcEndEffectoroperator= (const EcEndEffector &orig)
 assignment operator
 
EcBoolean operator== (const EcEndEffector &orig) const
 equality operator
 
virtual EcBoolean xmlInit () EC_OVERRIDE
 initialize XML components for reading and writing
 
virtual void registerComponents () EC_OVERRIDE
 registers components with the parent
 
virtual const EcStringlinkIdentifier () const
 gets the link identifier. This is the link to which the end-effector is attached.
 
virtual void setLinkIdentifier (const EcString &linkIdentifier)
 sets the link identifier. This is the link to which the end-effector is attached.
 
virtual EcBoolean changeLinkLabel (const EcString &fromLabel, const EcString &toLabel)
 
virtual const EcEndEffectorRelativeLinkDatarelativeLinkData () const
 gets the end-effector placement
 
virtual void setRelativeLinkData (const EcEndEffectorRelativeLinkData &relativeLinkData)
 sets the end-effector placement
 
virtual const EcBooleanisHardConstraint () const
 gets the is-hard-constraint flag
 
virtual void setIsHardConstraint (const EcBoolean &isHardConstraint)
 sets the is-hard-constraint flag
 
virtual const EcBooleanisEditable () const
 gets the is-editable flag
 
virtual void setIsEditable (const EcBoolean &isEditable)
 sets the is-editable flag
 
virtual void rightSizeJacobian (EcU32 startRow, EcU32 dof, EcManipulatorJacobian &jacobian) const
 
virtual void rightSizeSparsityDescriptionMatrix (EcU32 startRow, EcU32 dof, EcBooleanVectorVector &sparsityDescriptionMatrix) const
 
virtual EcU32 doc () const =0
 get the number of degrees of constraint for this end effector
 
virtual void insertJacobianComponent (const EcIndividualManipulator &manip, const EcU32 startRow, EcBoolean isFixedBase, EcManipulatorActiveState &activeState, EcManipulatorJacobian &jacobian) const =0
 build a strip of a Jacobian that corresponds to this end effector. More...
 
virtual void insertSparsityComponent (const EcIndividualManipulator &manip, const EcU32 startRow, EcBoolean isFixedBase, EcBooleanVectorVector &sparsityDescriptionMatrix) const =0
 
virtual void insertErrorWeightComponent (const EcU32 startRow, EcReArray &weights) const =0
 
virtual void calculatePlacement (const EcIndividualManipulator &manip, EcManipulatorActiveState &activeState, EcEndEffectorPlacement &placement) const =0
 Calculate a placement value for the end effector in the system coordinates. The placement is described through an EcEndEffectorPlacement, which may have different meanings for different end effector types. More...
 
virtual void calculatePlacementInRelative (const EcIndividualManipulator &manip, EcManipulatorActiveState &activeState, EcEndEffectorPlacement &placement) const
 Calculate a placement value for the end effector in the primary frame of the relative link. More...
 
virtual void calculateVelocity (const EcIndividualManipulator &manip, EcManipulatorActiveState &actState, EcXmlRealVector &velocity, EcU32 startInsertionIndex) const =0
 Calculate end effector velocity. The velocity may have different meanings for different end effector types. More...
 
virtual void calculateAcceleration (const EcIndividualManipulator &manip, EcManipulatorActiveState &actState, EcXmlRealVector &acceleration, EcU32 startInsertionIndex) const =0
 Calculate end effector acceleration. The acceleration may have different meanings for different end effector types. More...
 
virtual void filterEndEffectorVelocity (const EcIndividualManipulator &manip, const EcEndEffectorPlacement &guide, const EcXmlRealVector &inputVelocity, const EcXmlRealVector &lastVelocity, const EcXmlRealVector &lastAcceleration, EcReal timeStep, EcManipulatorActiveState &activeState, EcManipulatorActivePositionState &prevActivePositionState, EcXmlRealVector &filteredVelocity, EcXmlRealVector &filteredAcceleration) const =0
 
virtual void filterEndEffectorVelocity (const EcIndividualManipulator &manip, const EcXmlRealVector &inputVelocity, const EcXmlRealVector &lastVelocity, const EcXmlRealVector &lastAcceleration, EcReal timeStep, EcXmlRealVector &filteredVelocity, EcXmlRealVector &filteredAcceleration) const =0
 
virtual EcReal minimumTime (const EcEndEffectorPlacement &actual, const EcEndEffectorPlacement &desired) const =0
 
virtual EcReal difference (const EcEndEffectorPlacement &actual, const EcEndEffectorPlacement &desired) const =0
 
virtual const EcXmlStringVectoreditingLabels () const
 get the labels of all editable components
 
virtual const EcXmlStringVectortooltipLabels () const
 get the tooltips of all editable components
 
virtual const EcXmlStringVectoreditableValues () const =0
 get the values of all editable components
 
virtual void setEditableValues (const EcXmlStringVector &values)=0
 set the values of the editable components
 
virtual void setEditableValues ()
 set the values of the editable components (from the member variable)
 
virtual void setEditableValue (const EcU32 &index, const EcString &valueString)
 set the values of the editable component one at a time
 
virtual EcReal motionThreshold () const =0
 get the (end-effector specific) measure of the motion (velocity) threshold
 
virtual void setMotionThreshold (EcReal motionThreshold)=0
 set the (end-effector specific) measure of the motion (velocity) threshold
 
virtual EcReal accelerationThreshold () const =0
 get the (end-effector specific) measure of the acceleration threshold
 
virtual void setAccelerationThreshold (EcReal accelerationThreshold)=0
 set the (end-effector specific) measure of the acceleration threshold
 
virtual EcReal decelerationThreshold () const =0
 get the (end-effector specific) measure of the deceleration threshold
 
virtual void setDecelerationThreshold (EcReal value)=0
 set deceleration threshold
 
virtual EcBoolean copyMotionParams (const EcEndEffector &orig)=0
 
virtual EcBoolean convertPlacementFromSystemToRelative (const EcIndividualManipulator &manip, const EcEndEffectorPlacement &sysXForm, EcManipulatorActivePositionState &activePosState, EcEndEffectorPlacement &relXForm) const
 converts an end-effector placement from the system coordinates to the relative link's frame. If the end-effector doesn't have a relative link, relXForm is simply sysXForm. More...
 
virtual EcBoolean convertPlacementFromRelativeToSystem (const EcIndividualManipulator &manip, const EcEndEffectorPlacement &relXForm, EcManipulatorActivePositionState &activePosState, EcEndEffectorPlacement &sysXForm) const
 converts an end-effector placement from the relative link's frame to the system coordinates. If the end-effector doesn't have a relative link, sysXForm is simply relXForm. More...
 
virtual EcReal softConstraintMultiplier () const
 get the multiplier for soft-constraint error weights
 
virtual void setSoftConstraintMultiplier (EcReal value) const
 set the multiplier for soft-constraint error weights
 
virtual void calculateEndEffectorError (const EcIndividualManipulator &manip, const EcEndEffectorPlacement &goal, EcManipulatorActiveState &activeState, EcXmlRealVector &differential) const
 
virtual EcReal speedFactor () const
 
virtual void setSpeedFactor (EcReal value)
 set the speed factor
 
virtual EcReal accelerationFactor () const
 get the acceleration factor. This factor is multiplied with the acceleration/deceleration and jerk thresholds,
 
virtual void setAccelerationFactor (EcReal value)
 set the acceleration factor
 
virtual EcBoolean filteringActive () const
 
virtual void setFilteringActive (EcBoolean value)
 returns whether filtering is active.
 
virtual void setFilteringMode (const EcU32 value)
 Set filtering mode. More...
 
virtual const EcXmlStringendEffectorTooltip ()
 get end-effector tool-tip
 
virtual EcBoolean useExternalOffset () const
 get whether to use external offset.
 
virtual void setUseExternalOffset (EcBoolean value)
 
virtual EcU32 externalOffsetIndex () const
 get the index of the external offset to be used
 
virtual void setExternalOffsetIndex (EcU32 value)
 set the index of the external offset to be used
 
virtual void setExternalOffsetPointer (const EcCoordinateSystemTransformation *value)
 
virtual EcBoolean canBecomeSoft () const
 gets the flag indicating whether this end-effector can become soft (if it's hard)
 
virtual void setCanBecomeSoft (EcBoolean value)
 sets the flag indicating whether this end-effector can become soft (if it's hard)
 
virtual EcBoolean convertFromSystemToLocal (const EcIndividualManipulator &manip, const EcXmlRealVector &valueInSystem, EcManipulatorActiveState &activeState, EcXmlRealVector &valueInLocal) const
 convert a velocity or acceleration from system frame to local frame
 
virtual EcBoolean convertFromLocalToSystem (const EcIndividualManipulator &manip, const EcXmlRealVector &valueInLocal, EcManipulatorActiveState &activeState, EcXmlRealVector &valueInSystem) const
 convert a velocity or acceleration from local frame to system frame
 
virtual void setStoredDesiredPlacement (const EcEndEffectorPlacement &placement)
 set stored desired placement
 
virtual const EcEndEffectorPlacementstoredDesiredPlacement () const
 get stored desired placement
 
virtual void setAllowChangingDesiredPlacement (const EcBoolean &flag)
 set Allow Changing Desired Placement
 
virtual const EcBooleanallowChangingDesiredPlacement () const
 get Allow Changing Desired Placement
 
virtual void setControlMode (const EcU32 mode)
 sets the control mode More...
 
virtual EcU32 controlMode () const
 gets the control mode
 
- Public Member Functions inherited from EcXmlCompoundType
 ECDECLARE_BIGFOUR (EcXmlCompoundType)
 
virtual EcBoolean read (EcXmlReader &stream) EC_OVERRIDE
 read object from an XML stream
 
virtual EcBoolean readAttributes (EcXmlReader &stream)
 read object attributes from an XML stream
 
virtual EcBoolean readElements (EcXmlReader &stream)
 read object elements from an XML stream
 
virtual EcBoolean write (EcXmlWriter &stream) const EC_OVERRIDE
 write object to an XML stream
 
virtual EcBoolean writeAttributes (EcXmlWriter &stream) const
 write object attributes to an XML stream
 
virtual EcBoolean writeElements (EcXmlWriter &stream) const
 write object elements to an XML stream
 
virtual EcBoolean writeSchema (EcXmlSchema &stream) const EC_OVERRIDE
 write schema
 
virtual EcBoolean writeSchemaAttributes (EcXmlSchema &stream) const
 write schema attributes
 
virtual EcBoolean writeSchemaElements (EcXmlSchema &stream) const
 write schema elements
 
virtual void registerComponent (const EcToken &token, EcXmlObject *obj)
 register a single component More...
 
virtual void registerComponent (EcXmlObject *obj)
 register a single component More...
 
virtual void registerComponentReadOnly (const EcToken &token, EcXmlObject *obj)
 register a single component as read-only More...
 
virtual const EcXmlComponentMapcomponentMap () const
 get a reference to the component map
 
virtual void registerAttributeComponent (const EcToken &AttribToken, EcXmlObject *Obj)
 register a single attribute component More...
 
virtual void registerAttributeComponentReadOnly (const EcToken &AttribToken, EcXmlObject *Obj)
 register a single attribute component read-only More...
 
virtual const EcXmlComponentMapattributeComponentMap ()
 get a reference to the component attribute map
 
virtual const EcXmlSpecialDescriptorMapspecialDescriptorMap ()
 get a reference to the special-descriptor map
 
virtual void registerComponentDescriptor (const EcToken &xmlToken, const EcToken &descriptorToken, const EcString &descriptorString)
 register an XML token-string descriptor More...
 
virtual const EcXmlTokenStringDescriptorMapMaptokenStringDescriptorMap ()
 get a reference to the XML token-string descriptor map
 
virtual EcBoolean hasChildren () const
 return EcTrue if there are children components or EcFalse if an empty element.
 
virtual EcBoolean hasAttributes () const
 return EcTrue if there are attributes in the element.
 
- Public Member Functions inherited from EcXmlObject
 ECDECLARE_BIGFOUR (EcXmlObject)
 
virtual EcXmlObjectclone () const =0
 clone
 
virtual EcBoolean readAttribute (EcXmlReader &stream)
 read this attribute from an XML stream
 
virtual EcBoolean createSchema (const EcString &filename, const EcToken &objectName=EcXml::EcDefaultToken) const
 create schema
 
virtual EcBoolean xmlInitialized () const
 get XML initialized flag. This bit is set on initialization.
 
virtual void setXmlInitialized (EcBoolean val=EcTrue)
 set XML initialized flag. This bit is set on initialization.
 
virtual EcBoolean specified () const
 get specified flag. This bit is set upon reading from an XML file.
 
virtual void setSpecified (EcBoolean val=EcTrue)
 set specified flag. This bit is set upon reading from an XML file.
 
virtual EcBoolean isBasicType () const
 Return true/false for basic type.
 
virtual EcBoolean equalsDefault () const
 tests equality of XML object with default
 
virtual EcBoolean equality (const EcXmlObject *other) const =0
 equality - a virtual equality to an EcXmlObject pointer
 
virtual EcXmlObjectnewObject () const =0
 creates new object - a virtual new to an EcXmlObject pointer
 
virtual const EcTokentoken () const =0
 gets the xml token used for writing out.
 

Static Public Member Functions

static EcVector pointMotion (const EcManipulatorLink &inboardLink, const EcManipulatorLink &outboardLink, const EcVector &point, EcManipulatorActivePositionState &activePositionState)
 
static void getFrameMotion (const EcManipulatorLink &inboardLink, const EcManipulatorLink &outboardLink, const EcCoordinateSystemTransformation &frame, EcManipulatorActivePositionState &activePositionState, EcGeneralVelocity &frameMotion)
 
static EcVector pointPosition (const EcManipulatorLink &link, const EcVector &point, EcManipulatorActivePositionState &activePositionState)
 

Protected Member Functions

virtual void insertDefaultJointSparsityComponent (const EcIndividualManipulator &manip, const EcU32 startRow, EcBoolean isFixedBase, EcBooleanVectorVector &sparsityDescriptionMatrix) const
 
virtual void insertAllTrueBaseSparsityComponent (const EcIndividualManipulator &manip, const EcU32 startRow, EcBoolean isFixedBase, EcBooleanVectorVector &sparsityDescriptionMatrix) const
 
- Protected Member Functions inherited from EcXmlCompoundType
virtual EcBoolean readValueFromToken (const EcToken &token, EcXmlReader &stream)
 
virtual EcBoolean readValueFromSpecialToken (const EcToken &token, EcXmlReader &stream)
 read value from unregistered token
 
virtual EcBoolean readAttributeFromToken (const EcToken &token, EcXmlReader &stream)
 
virtual EcXmlComponentMapnewComponentMap () const
 allocate a new componentMap
 
virtual EcXmlSpecialDescriptorMapnewSpecialDescriptorMap ()
 allocate a new specialDescriptorsMap
 
virtual EcXmlTokenStringDescriptorMapMapnewTokenStringDescriptorMap ()
 allocate a new tokenStringDescriptorsMap
 
virtual void createComponentMap () const
 create component map
 
virtual void createAttributeComponentMap ()
 create attribute component map
 
virtual void createSpecialDescriptorMap ()
 create special-descriptors map
 
virtual void createTokenStringDescriptorMap ()
 create token-string descriptor map
 
virtual EcBoolean isReadOnlyComponent (const EcToken token) const
 check to see if the token corresponds to a read-only component
 
virtual EcBoolean isReadOnlyAttribute (const EcToken token) const
 check to see if the token corresponds to a read-only attribute
 
virtual EcXmlObjectlibraryAttribute ()
 

Protected Attributes

EcXmlString m_LinkIdentifier
 the string identifier for the link
 
EcEndEffectorRelativeLinkData m_RelativeLinkData
 the end-effector placement
 
EcXmlBoolean m_IsHardConstraint
 a flag indicating that this is a hard constraint
 
EcXmlBoolean m_IsEditable
 a flag indicating that this end effector is editable
 
EcXmlBoolean m_UseExternalOffset
 a flag indicating whether to use external offset
 
EcXmlU32 m_ExternalOffsetIndex
 Index of the external offset to be used.
 
EcXmlBoolean m_CanBecomeSoft
 a flag indicating whether this end-effector can become soft (if it's hard)
 
EcXmlStringVector m_EditingLabels
 the labels of all editable components
 
EcXmlStringVector m_EditableValues
 the values of all editable components
 
EcXmlU32 m_NumEditable
 number of Editable Value
 
EcXmlStringVector m_TooltipLabels
 the tooltips for editable components
 
EcEndEffectorPlacement m_StoredDesiredPlacement
 desired placement
 
EcXmlBoolean m_AllowChangingDesiredPlacement
 allow changing desired placement
 
EcXmlEnumU32 m_ControlMode
 the control model
 
EcReal m_SoftConstraintMultiplier
 non-XML data below More...
 
EcXmlString m_EeTooltip
 end-effector tooltip
 
const EcCoordinateSystemTransformationm_pExternalOffset
 pointer to the external offset
 
EcEndEffectorPlacement m_UtilityEndEffectorPlacment
 the utility end effector placement
 
- Protected Attributes inherited from EcXmlCompoundType
EcXmlComponentMapm_pComponentMap
 
EcXmlComponentMapm_pAttributeComponentMap
 
EcXmlSpecialDescriptorMapm_pSpecialDescriptorMap
 
EcXmlTokenStringDescriptorMapMapm_pComponentMapTokenStringDescriptor
 
- Protected Attributes inherited from EcXmlObject
EcU8 m_State
 the state of the object - eight boolean flags
 

Static Protected Attributes

static const EcU32 m_theBaseDof
 the degrees of freedom in a floating base
 
- Static Protected Attributes inherited from EcXmlObject
static const EcU8 m_theXmlInitializedBit
 the bit used to describe xml initialization
 
static const EcU8 m_theSpecifiedBit
 the bit used to describe specification
 

Detailed Description

Holds a base class for single end-effector components.

A base class for an end-effector component.

This class is responsible for the label identifier of the link to which the end effector is attached.

Examples:
ecProfilingMain.cpp, and ecQuickStartKinematicsMain.cpp.

Definition at line 32 of file ecEndEffector.h.

Member Function Documentation

virtual void EcEndEffector::calculateAcceleration ( const EcIndividualManipulator manip,
EcManipulatorActiveState actState,
EcXmlRealVector acceleration,
EcU32  startInsertionIndex 
) const
pure virtual

Calculate end effector acceleration. The acceleration may have different meanings for different end effector types.

Parameters
manipThe manipulator for this end effector
actStateThe manipulator active state
[out]accelerationThe placement of the end effector
startInsertionIndexThe index of acceleration vector at which this end effector acceleration should start

Implemented in EcCoordinatedJointEndEffector, EcSewAngleEndEffector, EcPointRotateEndEffector, EcLinearConstraintEndEffector, EcOneDofGripperEndEffector, EcPointDistanceEndEffector, EcAccelerometerEndEffector, EcProjectedCenterOfMassEndEffector, EcAxisRotateEndEffector, EcSpatialMomentumEndEffector, EcXyEndEffector, EcXEndEffector, EcOrientationEndEffector, EcPointEndEffector, EcCenterOfMassEndEffector, EcSagEndEffector, EcFlexGeneralSpatialEndEffector, EcFrameEndEffector, EcRCMEndEffector, EcSlideXSpinZEndEffector, EcSlidingEndEffector, EcFixedOrientationPointEndEffector, EcPlanarEndEffector, EcGeneralSpatialEndEffector, and EcFreeSpinInZEndEffector.

virtual void EcEndEffector::calculateEndEffectorError ( const EcIndividualManipulator manip,
const EcEndEffectorPlacement goal,
EcManipulatorActiveState activeState,
EcXmlRealVector differential 
) const
virtual

calculate an end-effector differential between the current and goal. the error is represented in a vector of size doc(). The derived class should implement this. By default, the implementation in this base class return the error of zero.

Parameters
[in]manipThe manipulator for this end effector
[in]goalThe goal placement
[in,out]activeStateThe manipulator active state
[out]differentialThe calculated end effector differential

Reimplemented in EcCoordinatedJointEndEffector, EcLinearConstraintEndEffector, EcXyEndEffector, EcXEndEffector, EcAxisRotateEndEffector, EcOneDofGripperEndEffector, EcFrameBasedEndEffector, EcOrientationEndEffector, EcFreeSpinInZEndEffector, and EcPointBasedEndEffector.

virtual void EcEndEffector::calculatePlacement ( const EcIndividualManipulator manip,
EcManipulatorActiveState activeState,
EcEndEffectorPlacement placement 
) const
pure virtual
virtual void EcEndEffector::calculatePlacementInRelative ( const EcIndividualManipulator manip,
EcManipulatorActiveState activeState,
EcEndEffectorPlacement placement 
) const
virtual

Calculate a placement value for the end effector in the primary frame of the relative link.

The default implementation just calls calculatePlacement and transforms the placement from the system frame to the primary frame of the relative link. The derived class may want to have its own, more efficient implementation.

Examples:
ecQuickStartKinematicsMain.cpp.
virtual void EcEndEffector::calculateVelocity ( const EcIndividualManipulator manip,
EcManipulatorActiveState actState,
EcXmlRealVector velocity,
EcU32  startInsertionIndex 
) const
pure virtual

Calculate end effector velocity. The velocity may have different meanings for different end effector types.

Parameters
manipThe manipulator for this end effector
actStateThe manipulator active state
[out]velocityThe placement of the end effector
startInsertionIndexThe index of velocity vector at which this end effector velocity should start

Implemented in EcCoordinatedJointEndEffector, EcSewAngleEndEffector, EcPointRotateEndEffector, EcLinearConstraintEndEffector, EcOneDofGripperEndEffector, EcPointDistanceEndEffector, EcAccelerometerEndEffector, EcProjectedCenterOfMassEndEffector, EcAxisRotateEndEffector, EcSpatialMomentumEndEffector, EcXyEndEffector, EcXEndEffector, EcOrientationEndEffector, EcPointEndEffector, EcCenterOfMassEndEffector, EcSagEndEffector, EcFlexGeneralSpatialEndEffector, EcFrameEndEffector, EcRCMEndEffector, EcSlideXSpinZEndEffector, EcSlidingEndEffector, EcFixedOrientationPointEndEffector, EcPlanarEndEffector, EcGeneralSpatialEndEffector, and EcFreeSpinInZEndEffector.

virtual EcBoolean EcEndEffector::changeLinkLabel ( const EcString fromLabel,
const EcString toLabel 
)
virtual

changes the link label inside end effector return true if a change is made

Reimplemented in EcOneDofGripperEndEffector, and EcLinearConstraintEndEffector.

virtual EcBoolean EcEndEffector::convertPlacementFromRelativeToSystem ( const EcIndividualManipulator manip,
const EcEndEffectorPlacement relXForm,
EcManipulatorActivePositionState activePosState,
EcEndEffectorPlacement sysXForm 
) const
virtual

converts an end-effector placement from the relative link's frame to the system coordinates. If the end-effector doesn't have a relative link, sysXForm is simply relXForm.

Parameters
[in]manipThe manipulator to which this end-effector belongs.
[in]relXFormThe end-effector placement in the relative link's frame.
[in,out]activePosStateThe active position state.
[out]sysXFormThe end-effector placement in system coordinates.
Returns
True if successful or false the relative link data is invalid, e.g. the linkID doesn't exist in the manipulator.

Reimplemented in EcXEndEffector.

virtual EcBoolean EcEndEffector::convertPlacementFromSystemToRelative ( const EcIndividualManipulator manip,
const EcEndEffectorPlacement sysXForm,
EcManipulatorActivePositionState activePosState,
EcEndEffectorPlacement relXForm 
) const
virtual

converts an end-effector placement from the system coordinates to the relative link's frame. If the end-effector doesn't have a relative link, relXForm is simply sysXForm.

Parameters
[in]manipThe manipulator to which this end-effector belongs.
[in]sysXFormThe end-effector placement in system coordinates.
[in,out]activePosStateThe active position state.
[out]relXFormThe end-effector placement in the relative link's frame.
Returns
True if successful or false the relative link data is invalid, e.g. the linkID doesn't exist in the manipulator.

Reimplemented in EcXEndEffector.

virtual EcBoolean EcEndEffector::copyMotionParams ( const EcEndEffector orig)
pure virtual

copy the motion parameters (speed, acceleration, etc.) from another end-effector must be of the same type.

Implemented in EcSpatialMomentumEndEffector, EcSagEndEffector, EcCoordinatedJointEndEffector, EcPointRotateEndEffector, EcSewAngleEndEffector, EcFrameBasedEndEffector, EcPointBasedEndEffector, EcRotationBasedEndEffector, and EcScalarBasedEndEffector.

virtual void EcEndEffector::filterEndEffectorVelocity ( const EcIndividualManipulator manip,
const EcEndEffectorPlacement guide,
const EcXmlRealVector inputVelocity,
const EcXmlRealVector lastVelocity,
const EcXmlRealVector lastAcceleration,
EcReal  timeStep,
EcManipulatorActiveState activeState,
EcManipulatorActivePositionState prevActivePositionState,
EcXmlRealVector filteredVelocity,
EcXmlRealVector filteredAcceleration 
) const
pure virtual

calculate an end-effector velocity that drives the end effector toward the guide (desired) placement. The calculated velocity is typically constrained by the motion filter of the end effector unless filtering is not active. The filtered velocity is expressed through an EcXmlRealVector. The guide frame is always represented in system coordinates.

Parameters
[in]manipThe manipulator for this end effector
[in]guideThe guide (desired) placement
[in]inputVelocityThe desired end effector velocity. The will be added to the velocity that would drive the end effector toward the guide.
[in]lastVelocityThe current end effector velocity (normally computed from previous step)
[in]lastAccelerationThe current end effector acceleration (normally computed from previous step)
[in]timeStepThe time step
[in,out]activeStateThe manipulator active state
[in,out]previousactiveState
[out]filteredVelocityThe calculated end effector velocity
[out]filteredAccelerationThe calculated end effector acceleration
See also
setFilteringActive()

Implemented in EcCoordinatedJointEndEffector, EcSewAngleEndEffector, EcPointRotateEndEffector, EcSagEndEffector, EcLinearConstraintEndEffector, EcOneDofGripperEndEffector, EcFrameBasedEndEffector, EcProjectedCenterOfMassEndEffector, EcPointDistanceEndEffector, EcAccelerometerEndEffector, EcXyEndEffector, EcXEndEffector, EcAxisRotateEndEffector, EcSpatialMomentumEndEffector, EcOrientationEndEffector, EcFlexGeneralSpatialEndEffector, EcFixedOrientationPointEndEffector, EcGeneralSpatialEndEffector, EcRCMEndEffector, EcSlideXSpinZEndEffector, EcSlidingEndEffector, EcPlanarEndEffector, EcFreeSpinInZEndEffector, and EcPointBasedEndEffector.

virtual void EcEndEffector::filterEndEffectorVelocity ( const EcIndividualManipulator manip,
const EcXmlRealVector inputVelocity,
const EcXmlRealVector lastVelocity,
const EcXmlRealVector lastAcceleration,
EcReal  timeStep,
EcXmlRealVector filteredVelocity,
EcXmlRealVector filteredAcceleration 
) const
pure virtual

filter an input end-effector velocity by applying velocity and acceleration thresholds

Parameters
[in]manipThe manipulator for this end effector
[in]inputVelocityThe desired end effector velocity
[in]lastVelocityThe current end effector velocity (normally computed from previous step)
[in]lastAccelerationThe current end effector acceleration(normally computed from previous step)
[in]timeStepThe time step
[out]filteredVelocityThe calculated end effector velocity
[out]filteredAccelerationThe calculated end effector acceleration

Implemented in EcCoordinatedJointEndEffector, EcSewAngleEndEffector, EcPointRotateEndEffector, EcSagEndEffector, EcLinearConstraintEndEffector, EcOneDofGripperEndEffector, EcFrameBasedEndEffector, EcPointDistanceEndEffector, EcAccelerometerEndEffector, EcAxisRotateEndEffector, EcSpatialMomentumEndEffector, EcOrientationEndEffector, EcFreeSpinInZEndEffector, and EcPointBasedEndEffector.

virtual EcBoolean EcEndEffector::filteringActive ( ) const
virtual

returns whether filtering is active. If it is, then the velocity will be filtered according to the filtering mode. If not, then the velocity will be computed such that the returned velocity will result in the goal is accomplished in one step.

Reimplemented in EcCoordinatedJointEndEffector, EcFrameBasedEndEffector, EcDirectionalFrameEndEffector, EcOrientationEndEffector, EcPointBasedEndEffector, EcRotationBasedEndEffector, and EcScalarBasedEndEffector.

static void EcEndEffector::getFrameMotion ( const EcManipulatorLink inboardLink,
const EcManipulatorLink outboardLink,
const EcCoordinateSystemTransformation frame,
EcManipulatorActivePositionState activePositionState,
EcGeneralVelocity frameMotion 
)
static

calculate the general velocity of a frame in the outboard link's primary frame due to unit joint motion of the inboard link. (i.e., 1 m/s or 1 rad/s)

virtual void EcEndEffector::insertAllTrueBaseSparsityComponent ( const EcIndividualManipulator manip,
const EcU32  startRow,
EcBoolean  isFixedBase,
EcBooleanVectorVector sparsityDescriptionMatrix 
) const
protectedvirtual

This will mark all entries for the base portion of a sparsity description matrix as true if isFixedBase is true and the end effector is not relative. Do nothing otherwise. This can be used in the derived class' implementation of insertSparsityComponent if appropriate. Note that this method assume that sparsityDescriptionMatrix is correctly sized.

Parameters
manipThe manipulator for this end effector
startRowThe row index to start inserting the sparsity component from this end effector
isFixedBaseA flag indicating whether or not the base is fixed
sparsityDescriptionMatrixThe matrix with a sparsity strip for this end effector
See also
insertSparsityComponent
virtual void EcEndEffector::insertDefaultJointSparsityComponent ( const EcIndividualManipulator manip,
const EcU32  startRow,
EcBoolean  isFixedBase,
EcBooleanVectorVector sparsityDescriptionMatrix 
) const
protectedvirtual

default implementation to build a joint portion of a sparsity description matrix This can be used in the derived class' implementation of insertSparsityComponent if appropriate. This handles the end effector and relative links in general case. Note that this method will also correctly resize sparsityDescriptionMatrix

Parameters
manipThe manipulator for this end effector
startRowThe row index to start inserting the sparsity component from this end effector
isFixedBaseA flag indicating whether or not the base is fixed
sparsityDescriptionMatrixThe matrix with a sparsity strip for this end effector
See also
insertSparsityComponent
virtual void EcEndEffector::insertJacobianComponent ( const EcIndividualManipulator manip,
const EcU32  startRow,
EcBoolean  isFixedBase,
EcManipulatorActiveState activeState,
EcManipulatorJacobian jacobian 
) const
pure virtual

build a strip of a Jacobian that corresponds to this end effector.

Parameters
manipThe manipulator for this end effector
startRowThe row index to start inserting the Jacobian component from this end effector
isFixedBaseA flag indicating whether or not the base is fixed
[in,out]activeStateThe manipulator active state
[out]jacobianThe Jacobian with a strip for this end effector

Implemented in EcCoordinatedJointEndEffector, EcSewAngleEndEffector, EcPointRotateEndEffector, EcLinearConstraintEndEffector, EcOneDofGripperEndEffector, EcAccelerometerEndEffector, EcPointDistanceEndEffector, EcAxisRotateEndEffector, EcSpatialMomentumEndEffector, EcProjectedCenterOfMassEndEffector, EcXEndEffector, EcXyEndEffector, EcOrientationEndEffector, EcPointEndEffector, EcSagEndEffector, EcCenterOfMassEndEffector, EcFlexGeneralSpatialEndEffector, EcRCMEndEffector, EcSlideXSpinZEndEffector, EcSlidingEndEffector, EcFixedOrientationPointEndEffector, EcFrameEndEffector, EcPlanarEndEffector, EcGeneralSpatialEndEffector, and EcFreeSpinInZEndEffector.

virtual void EcEndEffector::insertSparsityComponent ( const EcIndividualManipulator manip,
const EcU32  startRow,
EcBoolean  isFixedBase,
EcBooleanVectorVector sparsityDescriptionMatrix 
) const
pure virtual

build a strip of a sparsity description matrix (with true where there may be nonzero values and false where there cannot be nonzero values)

Parameters
manipThe manipulator for this end effector
startRowThe row index to start inserting the sparsity component from this end effector
isFixedBaseA flag indicating whether or not the base is fixed
sparsityDescriptionMatrixThe matrix with a sparsity strip for this end effector

Implemented in EcCoordinatedJointEndEffector, EcSewAngleEndEffector, EcPointRotateEndEffector, EcLinearConstraintEndEffector, EcOneDofGripperEndEffector, EcAccelerometerEndEffector, EcPointDistanceEndEffector, EcAxisRotateEndEffector, EcSpatialMomentumEndEffector, EcProjectedCenterOfMassEndEffector, EcXEndEffector, EcXyEndEffector, EcOrientationEndEffector, EcPointEndEffector, EcSagEndEffector, EcCenterOfMassEndEffector, EcFlexGeneralSpatialEndEffector, EcRCMEndEffector, EcSlideXSpinZEndEffector, EcSlidingEndEffector, EcFixedOrientationPointEndEffector, EcFrameEndEffector, EcPlanarEndEffector, EcGeneralSpatialEndEffector, and EcFreeSpinInZEndEffector.

static EcVector EcEndEffector::pointMotion ( const EcManipulatorLink inboardLink,
const EcManipulatorLink outboardLink,
const EcVector point,
EcManipulatorActivePositionState activePositionState 
)
static

calculate the velocity of the point in the outboard link's primary frame due to unit joint motion of the inboard link. (i.e., 1 m/s or 1 rad/s)

static EcVector EcEndEffector::pointPosition ( const EcManipulatorLink link,
const EcVector point,
EcManipulatorActivePositionState activePositionState 
)
static

calculate the location of a point in system coordinates. The input point vector is represented in link coordinates

virtual void EcEndEffector::rightSizeJacobian ( EcU32  startRow,
EcU32  dof,
EcManipulatorJacobian jacobian 
) const
virtual

make sure the Jacobian is the right size for this end effector starting at the startRow position.

virtual void EcEndEffector::rightSizeSparsityDescriptionMatrix ( EcU32  startRow,
EcU32  dof,
EcBooleanVectorVector sparsityDescriptionMatrix 
) const
virtual

make sure the sparsity description matrix is the right size for this end effector starting at the startRow position.

virtual void EcEndEffector::setControlMode ( const EcU32  mode)
virtual

sets the control mode

Parameters
[in]modeThe control mode, either POSITION_CONTROL, VELOCITY_CONTROL, or PROFILED_POSITION

Reimplemented in EcCoordinatedJointEndEffector.

virtual void EcEndEffector::setExternalOffsetPointer ( const EcCoordinateSystemTransformation value)
virtual

the pointer to the external offset. The offset is the offset from the end-effector's frame or point. For example, a frame end-effector may define the frame that puts the end-effector at the tool plate. The offset is then defined relative to the tool plate.

virtual void EcEndEffector::setFilteringMode ( const EcU32  value)
virtual

Set filtering mode.

Parameters
[in]valuethe filtering mode. See EcBaseMotionFilter::FilteringMode

Reimplemented in EcCoordinatedJointEndEffector, EcFrameBasedEndEffector, and EcPointBasedEndEffector.

virtual void EcEndEffector::setUseExternalOffset ( EcBoolean  value)
virtual

set whether to use external offset. This allows multiple end-effectors to share the same offset and allows easy changing of the offset at run time. Note that not all end-effector types can use offsets. Only end-effectors that define a frame or a point can use offsets.

virtual EcReal EcEndEffector::speedFactor ( ) const
virtual

get the speed factor. This factor is multiplied with the velocity threshold, thus allowing the end-effector speed to be adjusted at run-time. By default, this is 1.

Reimplemented in EcCoordinatedJointEndEffector, EcSewAngleEndEffector, EcPointRotateEndEffector, EcFrameBasedEndEffector, EcDirectionalFrameEndEffector, EcOrientationEndEffector, EcPointBasedEndEffector, EcRotationBasedEndEffector, and EcScalarBasedEndEffector.

Member Data Documentation

EcReal EcEndEffector::m_SoftConstraintMultiplier
mutableprotected

non-XML data below

the multiplier for soft-constraint error weights

Definition at line 725 of file ecEndEffector.h.


The documentation for this class was generated from the following file:
Created by Energid Technologies www.energid.com
Copyright © 2016 Energid. All trademarks mentioned in this document are property of their respective owners.