Actin  Version 5.5.2
Software for Robotics Simulation and Control
EcStatedSystem Class Reference

Holds a description of the manipulator system and its state. More...

#include <ecStatedSystem.h>

Inheritance diagram for EcStatedSystem:
[legend]
Collaboration diagram for EcStatedSystem:
[legend]

Public Types

enum  {
  NOCOLLISIONAVOIDANCE,
  SYSTEMCOLLISIONAVOIDANCE,
  MANIPULATORCOLLISIONAVOIDANCE,
  RECORDCOLLISIONSONLY
}
 collision avoidance modes
 
- Public Types inherited from EcXmlCompoundType
enum  {
  READONLYCOMPONENT = 0,
  READONLYATTRIBUTE
}
 special-descriptor codes More...
 

Public Member Functions

 EcStatedSystem ()
 default constructor
 
virtual ~EcStatedSystem ()
 destructor
 
 EcStatedSystem (const EcStatedSystem &orig, EcFoundCommon::DeepCopyFlag copyFlag=EcFoundCommon::CopyNone)
 copy constructor More...
 
EcStatedSystemoperator= (const EcStatedSystem &orig)
 assignment operator
 
EcBoolean operator== (const EcStatedSystem &orig) const
 equality operator
 
virtual EcBoolean mergeWith (const EcStatedSystem &orig)
 merge operation
 
virtual EcBoolean xmlInit () EC_OVERRIDE
 initialize XML components for reading and writing
 
virtual EcXmlObjectclone () const EC_OVERRIDE
 clone - a virtual constructor to an EcXmlObject pointer
 
virtual void registerComponents () EC_OVERRIDE
 registers components with the parent
 
virtual EcBoolean equality (const EcXmlObject *other) const EC_OVERRIDE
 equality - virtual equality to an EcXmlObject pointer
 
virtual EcXmlObjectnewObject () const EC_OVERRIDE
 virtual new that returns an EcXmlObject
 
virtual const EcManipulatorSystemsystem () const
 gets the system
 
virtual void setSystem (const EcManipulatorSystem &system)
 sets the system
 
virtual void setAndDeleteSystemPointer (EcManipulatorSystem *pSystem)
 sets the system pointer (and later deletes this pointer)
 
virtual void setFromSystem (const EcManipulatorSystem &system)
 
virtual void setFromManipulator (const EcIndividualManipulator &manipulator)
 
virtual EcIndividualManipulatorclearAndInitializeForOneManipulator ()
 
virtual void finalizeOneManipulator ()
 
virtual void addManipulator (const EcIndividualManipulator &manipulator, const EcPositionState &positionState, const EcVelocityState &velocityState)
 add a manipulator with the specified position and velocity states
 
virtual void addManipulator (const EcIndividualManipulator &manipulator)
 add a manipulator using default position and velocity states
 
virtual EcBoolean exchangeManipulator (EcU32 manipulatorIndex, const EcIndividualManipulator &manipulator, const EcPositionState &positionState, const EcVelocityState &velocityState)
 
virtual EcU32 addShapeAsManipulator (const EcShape &shape, const EcCoordinateSystemTransformation &pose, const EcString &label, const EcDataMap &color=EcSurfaceColorFactory::boundingColor())
 
virtual EcBoolean changeManipulatorLabel (const EcString &manipLabel, const EcString &newLabel)
 change manipulator label
 
virtual const EcIndividualManipulatormanipulatorByIdentifier (const EcString &label) const
 return manipulator by label
 
virtual const EcIndividualManipulatormanipulatorByIndex (EcU32 index) const
 return manipulator by index
 
virtual EcU32 numberOfManipulators () const
 return the number of manipulators
 
virtual EcBoolean setSelfCollisionMap (const EcManipulatorSelfCollisionLinkMap &map, const EcU32 &manipID)
 set the self collision map for manipulator manipID
 
virtual EcInt32 deleteManipulator (const EcString &manipLabel)
 delete a manipulator and corresponding position and velocity states by label. More...
 
virtual EcBoolean deleteManipulator (EcU32 manipIndex)
 delete a manipulator and corresponding position and velocity states by index. More...
 
virtual const EcSystemEnvironmentenvironment () const
 gets upward pointing gravity vector and other environmental data
 
virtual void setEnvironment (const EcSystemEnvironment &environment)
 sets upward pointing gravity vector and other environmental data
 
virtual const EcManipulatorSystemStatestate () const
 gets the state
 
virtual void setState (const EcManipulatorSystemState &state)
 sets the state
 
virtual void setIndividualPositionState (EcU32 manipulatorIndex, const EcPositionState &positionState)
 sets a position state for an individual manipulator
 
virtual void setIndividualCoordinateSystemTransformation (EcU32 manipulatorIndex, const EcCoordinateSystemTransformation &xform)
 sets a base position and orientation for an individual manipulator
 
virtual void setIndividualVelocityState (EcU32 manipulatorIndex, const EcVelocityState &velocityState)
 sets a velocity state for an individual manipulator
 
virtual void setIndividualBaseVelocity (EcU32 manipulatorIndex, const EcGeneralVelocity &baseVelocity)
 sets a base velocity for an individual manipulator
 
virtual void rotateIndividualBaseVelocity (EcU32 manipulatorIndex, const EcOrientation &orient)
 rotate the linear and angular velocity of the base of one manipulator
 
virtual void zeroIndividualVelocityState (EcU32 manipulatorIndex)
 zeros a velocity state for an individual manipulator
 
virtual void setPositionStates (const EcPositionStateVector &positionStates)
 sets position states
 
virtual void setVelocityStates (const EcVelocityStateVector &velocityStates)
 sets velocity states
 
void setAccelerationStates (const EcAccelerationStateVector &accelerationStates)
 sets the acceleration states
 
virtual const EcManipulatorSystemConfigurationconfiguration () const
 gets the configuration, which changes intermittently – const version
 
virtual EcManipulatorSystemConfigurationconfiguration ()
 gets the configuration, which changes intermittently – non-const version
 
EcBoolean setNamedFrames (const EcU32 manIndex, const EcU32 linkIndex, const EcNamedFrames &namedFrames)
 
virtual void setConfiguration (const EcManipulatorSystemConfiguration &value)
 sets the configuration
 
virtual void setProximityTool (const EcBaseProximityTool &value)
 set the proximity tool
 
virtual void propagateSelfTo (EcReal newTime, EcSystemActiveState *pActState=EcNULL)
 
virtual void propagateSelfTo (EcReal newTime, EcPropagationResultDataVector &resultDataVector, EcSystemActiveState *pActState=EcNULL)
 
virtual void propagateSelfTo (EcReal newTime, EcPropagationResultDataVector &resultDataVector, EcSystemActiveState *pActState, EcU32 collisionAvoidanceMode, const EcReal &collisionBreakthroughThreshold, const EcU32 &bvLevel, const EcReal &precision)
 
virtual void propagateTo (EcReal newTime, EcManipulatorSystemState &state, EcSystemActiveState *pActState=EcNULL) const
 
virtual void propagateTo (EcReal newTime, EcManipulatorSystemState &state, EcPropagationResultDataVector &resultDataVector, EcSystemActiveState &actState) const
 
virtual void propagateTo (EcReal newTime, EcManipulatorSystemState &state, EcPropagationResultDataVector &resultDataVector, EcSystemActiveState &actState, EcU32 collisionAvoidanceMode, const EcReal &collisionBreakthroughThreshold, const EcU32 &bvLevel, const EcReal &precision) const
 
virtual void propagateVelocityAndPositionStateTo (EcReal newTime, EcManipulatorSystemState &state, EcSystemActiveState &actState) const
 
virtual void propagateSingleStateBy (EcU32 index, const EcVelocityState &velocityState, EcReal deltaT, EcPositionState &positionState) const
 
virtual void propagateSingleStateBy (EcU32 index, const EcVelocityState &velocityState, EcReal deltaT, EcPositionState &positionState, EcPropagationResultData &resultData) const
 
virtual void propagateSingleVelocityStateBy (EcU32 index, const EcAccelerationState &accelerationState, EcReal deltaT, EcVelocityState &velocityState) const
 propagate a single velocity state by delta-t using the acceleration state. The manipulator number is given by index.
 
virtual void addCompatibleState ()
 Add a zero state that is compatible with the system.
 
virtual void setToMidpointState ()
 Add a state that has each joint position halfway between joint limits.
 
virtual void rightSizeState (EcManipulatorSystemState &state) const
 
virtual EcSphere absoluteBoundingSphere () const
 
const EcShapeshapeByKey (const EcShapeStateCacheKey &key) const
 get a shape by the key. the key is (manipID,linkID,shapeID)
 
virtual EcBoolean setSurfacesByKey (const EcShapeStateCacheKey &key, const EcStringDataMapMap &surfaces)
 Set shape surface properties by the key.
 
virtual const EcShapeStateCacheKeyVectormodifiedShapeKeyVec () const
 
virtual EcShapeStateCacheKeyVectormodifiedShapeKeyVec ()
 gets the vector of the modified shape key (non const version)
 
virtual void setModifiedShapeKeyVec (const EcShapeStateCacheKeyVector &modifiedShapeKeyVec)
 sets the vector of deformed shape key
 
virtual void addModifiedShapeKeyVec (const EcShapeStateCacheKey &modifiedShapeKey)
 add the modified shape key
 
virtual EcBoolean isTransparentDisplay () const
 gets the flag for the transparent rendering
 
virtual void setIsTransparentDisplay (const EcBoolean change) const
 sets the flag for the transparent rendering
 
virtual void intersectLineSegment (const EcLineSegment &lineSegment, EcSystemPointEvent &pointEvent, EcSystemActiveState *pActState, EcU32 levelOfDetail=0) const
 intersect a line segment with the full system
 
virtual EcBoolean scaleManipulatorBy (EcU32 manipulatorIndex, EcReal scaleFactor)
 
virtual EcBoolean findAndConvertToReferences ()
 
virtual const EcU32 jointDof (const EcU32 &index) const
 get the joint dof of the manipulator at index index
 
virtual EcBoolean setJointLimit (EcU32 manipulatorIndex, const EcString &linkLabel, EcBoolean isLowerLimit, EcReal value)
 set the new value for a joint limit More...
 
virtual EcBoolean replaceLinkProperties (EcU32 manipulatorIndex, const EcString &linkLabel, const EcManipulatorLink &newLink, EcBoolean includeShapeContainer=EcFalse)
 replace the link properties (link kinematics, mass properties, joint actuator, shape container, etc.) of the link identified by linkLabel with the properties of newLink. More...
 
virtual const EcTokentoken () const EC_OVERRIDE
 gets the xml token used for writing out. More...
 
virtual EcBoolean read (EcXmlReader &stream) EC_OVERRIDE
 read this object from an XML stream
 
virtual EcBoolean write (EcXmlWriter &stream) const EC_OVERRIDE
 write this object to an XML stream
 
virtual EcBoolean generateCollisionReport (EcPropagationResultDataVector &collisions, const EcU32 &bvLevel=1, const EcReal &precision=0) const
 
virtual EcBoolean isSystemModified () const
 returns true if the system has recently been modified. This is useful for rendering since it needs to grab internal pointers of the system and if it has been modified, those pointers will be invalid. Rendering can check it and if the system has just been modified, it can grab new pointers.
 
virtual void resetIsSystemModified () const
 sets isSystemModified to false. Rendering should call this after it's done grabbing new pointers to the system internals.
 
virtual void truncateValues (const EcReal &precision=1e-10)
 truncate values in the physical extents to the precision specified.
 
virtual void changeAmbientAlpha (const EcShapeStateCacheKey &key, const EcReal &transparencyLevel)
 change the Ambient Alpha value for a surface given a Shape key (assumed shapeID = 0)
 
virtual void changeDiffuseAlpha (const EcShapeStateCacheKey &key, const EcReal &transparencyLevel)
 change the Ambient Alpha value for a surface given a Shape key (assumed shapeID = 0)
 
virtual void changeSpecularAlpha (const EcShapeStateCacheKey &key, const EcReal &transparencyLevel)
 change the Ambient Alpha value for a surface given a Shape key (assumed shapeID = 0)
 
virtual void changeEmissionAlpha (const EcShapeStateCacheKey &key, const EcReal &transparencyLevel)
 change the Ambient Alpha value for a surface given a Shape key (assumed shapeID = 0)
 
virtual const EcShapeStateCacheKeyVectorselectedShapeKeyVector () const
 get the selected Shape Key vector for rendering their member's transparency
 
virtual void setSelectedShapeKeyVector (const EcShapeStateCacheKeyVector &keyVector)
 set the selected Shape Key vector for rendering their member's transparency
 
virtual const EcReal transparencyAlpha () const
 get the transparency level
 
virtual void setTransparencyAlpha (const EcReal alphaValue)
 set the transparency level
 
virtual EcBoolean isSelectionDataChanged () const
 check if there's any change in the AnatomySelector dialog
 
virtual void setIsSelectionDataChanged (const EcBoolean change) const
 set the flag telling if there's any change in the AnatomySelector dialog
 
virtual void setCollisionExclusionMap (const EcSystemCollisionExclusionMap &value)
 set the static (system) collision exclusion map
 
virtual void setDynamicCollisionExclusionMap (const EcSystemCollisionExclusionMap &value)
 set the dynamic (runtime) collision exclusion map
 
virtual const EcSystemCollisionExclusionMapcollisionExclusionMapForCA () const
 returns the collision map for collision avoidance
 
virtual void setSollisionExclusionMapForCA (const EcSystemCollisionExclusionMap &value)
 set collision exclusion map for collision avoidance
 
virtual void setManipulatorAttachmentMap (const EcManipulatorAttachmentMap &value)
 set the manipulator attachment map
 
virtual const EcPositionStateVectorlastPositionStateVector ()
 
virtual EcBoolean lookupManipulatorIndexFromLabel (const EcString &label, EcU32 &manipIndex) const
 get the manipulator index from base link label
 
virtual EcBoolean canCollide (EcU32 manip1Index, EcU32 link1Index, EcU32 manip2Index, EcU32 link2Index, EcBoolean collisionAvoidance=EcFalse) const
 
virtual EcBoolean combineManipulator (const EcU32 depManipIndex, const EcU32 baseManipIndex, const EcString &baseLinkLabel, const EcCoordinateSystemTransformation &offset)
 rigidly combine manipulators based on the attachment
 
virtual EcBoolean uncombineManipulator (const EcString &depManipLabel, EcString &baseManipLabel, EcString &baseLinkLabel)
 uncombine manipulator
 
virtual EcBoolean replaceLinkShape (EcU32 manipIndex, const EcString &linkLabel, const EcShape &shape, EcU32 bvhLevel, EcBoolean alwaysReplace=EcFalse)
 
virtual EcBoolean replaceLinkShape (EcU32 manipIndex, const EcU32 linkIndex, const EcShape &shape, EcU32 bvhLevel, EcBoolean alwaysReplace=EcFalse)
 
virtual EcBoolean replaceLinkKinematics (EcU32 manipIndex, const EcString &linkLabel, const EcLinkKinematics &newKinematics)
 
virtual void makeDeepCopy (EcFoundCommon::DeepCopyFlag copyFlag)
 
void simplifyManipulators ()
 simplify manipulators
 
virtual void setBuildShapeLevelAABB (EcBoolean buildShapeLevel)
 set whether to build AABB at shape level More...
 
ecboost::shared_ptr< EcManipulatorSystemsystemSharedPtr ()
 
virtual void setManipulatorCanBeStatic (EcU32 manipIndex, EcBoolean setStatic)
 
virtual void setManipulatorIsReferencedBy (EcU32 manipIndex, EcBoolean isReferencedBy)
 Set the manipulatorIsReferencedBy flag to true for the given manipIndex.
 
virtual void propagateAttachedManipulatorStates (EcManipulatorSystemState &state, EcSystemActiveState &actState) const
 
- Public Member Functions inherited from EcXmlCompoundType
 ECDECLARE_BIGFOUR (EcXmlCompoundType)
 
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 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 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
 

Static Public Member Functions

static EcStatedSystem nullObject ()
 get a null stated system
 

Protected Member Functions

virtual EcBaseProximityToolproximityTool ()
 get a non-const pointer to the proximity tool.
 
virtual const EcBaseProximityToolproximityTool () const
 get a const pointer to the proximity tool.
 
virtual EcBoolean validateTopLevelDimensions ()
 ensure a match in the numbers of manipulators
 
virtual EcBoolean validateLowLevelDimensions ()
 ensure a match in the sizes of manipulators
 
virtual void aboutToModifySystem ()
 update reference counting data to prepare for modification
 
virtual EcBoolean checkForCollisions (EcSystemActiveState &systemActiveState, const EcReal &collisionBreakthroughThreshold, const EcU32 &bvLevel, const EcReal &precision, EcPropagationResultDataVector &results) const
 check for manipulator collisions
 
virtual void updateCurrentlyStaticManipVector ()
 
virtual void updateSingleManipCurrentlyStatic (EcU32 manipIndex)
 
- 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

ecboost::shared_ptr< EcManipulatorSystemm_pSystemOld
 a pointer to the system, which does not change – deprecated
 
EcManipulatorSystemContainer m_SystemContainer
 manipulator system container
 
EcManipulatorSystemState m_State
 the state, which changes constantly
 
EcManipulatorSystemConfiguration m_Configuration
 the configuration, which changes intermittently
 
EcPositionStateVector m_LastPositionStateVector
 a vector of position states used for collision detection
 
ecboost::shared_ptr< EcSystemActiveStatem_pCurrentSystemActiveState
 a utility vector of position states used for collision detection
 
ecboost::shared_ptr< EcSystemActiveStatem_pStaticSystemActiveState
 
EcPropagationResultDataVector m_IterativeResultsVector
 a utility vector of propagation information results for iteration
 
EcPropagationResultDataVector m_UtilityResultsDataVector
 a utility vector of propagation information results
 
EcShapeStateCacheKeyVector m_ModifiedShapeKeyVec
 vector to store the modified shapes by key
 
EcBoolean m_IsSystemModified
 a flag indicating whether or not the system has just been modified
 
EcShapeStateCacheKeyVector m_SelectedShapeKeyVector
 vector to store selected viewable shapes by key
 
EcReal m_TransparencyAlpha
 alpha value for transparency
 
EcBoolean m_IsSelectionDataChanged
 change made by user via AnatomySelector Dialog
 
EcBoolean m_IsTransparentDisplay
 picked for visualization parameter changes
 
EcProximityToolContainer m_ProximityToolContainer
 the proximity tool used to compute distances
 
- 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
 

Additional Inherited Members

- 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 description of the manipulator system and its state.

A description of a manipulator system with a state.

Examples:
ecCollisionAvoidanceExample.cpp, and ecProgrammaticConstructionMain.cpp.

Definition at line 30 of file ecStatedSystem.h.

Constructor & Destructor Documentation

EcStatedSystem::EcStatedSystem ( const EcStatedSystem orig,
EcFoundCommon::DeepCopyFlag  copyFlag = EcFoundCommon::CopyNone 
)

copy constructor

Parameters
[in]origStatedSystem to copy from
[in]copyFlag
See also
EcFoundCommon::DeepCopyFlag.

Member Function Documentation

virtual EcSphere EcStatedSystem::absoluteBoundingSphere ( ) const
virtual

calculate a bounding sphere. This bounding sphere is not a function of the joint positions (though it is a function of the manipulator base positions and orientations.

virtual EcU32 EcStatedSystem::addShapeAsManipulator ( const EcShape shape,
const EcCoordinateSystemTransformation pose,
const EcString label,
const EcDataMap color = EcSurfaceColorFactory::boundingColor() 
)
virtual

add a shape as a manipulator, with the specified position and orientation returns the index of the new manipulator

virtual EcBoolean EcStatedSystem::canCollide ( EcU32  manip1Index,
EcU32  link1Index,
EcU32  manip2Index,
EcU32  link2Index,
EcBoolean  collisionAvoidance = EcFalse 
) const
virtual

returns a boolean describing if two links on two DIFFERENT manipulators can collide. This uses both static (in system) and dynamic (in configuration) collision exclusion maps. If collisionAvoidance is true, it will also check using the collisionExclusionMapForCA in configuration as well.

virtual EcIndividualManipulator& EcStatedSystem::clearAndInitializeForOneManipulator ( )
virtual

clears this stated system and initializes it for having a single manipulator. This manipulator is returned by reference so that it can be set externally without the use of a copy. After this reference is set, finalizeForSingleManipulator() must be called. Use with caution.

virtual EcInt32 EcStatedSystem::deleteManipulator ( const EcString manipLabel)
virtual

delete a manipulator and corresponding position and velocity states by label.

Parameters
[in]manipLabelThe string label of the manipulator to be deleted. In case of manipulators with duplicated label, the first manipulator with the label matched with manipLabel will be deleted.
Returns
The index of the deleted manipulator if the manipulator was found and successfully deleted. If the manipulator was not found, then this returns -1.
virtual EcBoolean EcStatedSystem::deleteManipulator ( EcU32  manipIndex)
virtual

delete a manipulator and corresponding position and velocity states by index.

Parameters
[in]manipIndexThe index of the manipulator to be deleted.
Returns
True if manipIndex is valid and the manipulator is successfully deleted or false otherwise.
virtual EcBoolean EcStatedSystem::exchangeManipulator ( EcU32  manipulatorIndex,
const EcIndividualManipulator manipulator,
const EcPositionState positionState,
const EcVelocityState velocityState 
)
virtual

exchange an existing manipulator with a new manipulator having the specified position and velocity states

virtual void EcStatedSystem::finalizeOneManipulator ( )
virtual

with the first manipulator properly set, this method sets the proper state. It should be used only with clearAndInitializeForOneManipulator().

virtual EcBoolean EcStatedSystem::findAndConvertToReferences ( )
virtual

find and convert explicit manipulator link descriptions to references where possible

virtual EcBoolean EcStatedSystem::generateCollisionReport ( EcPropagationResultDataVector collisions,
const EcU32 bvLevel = 1,
const EcReal precision = 0 
) const
virtual

generate a collision report based on the current state of the system.

virtual void EcStatedSystem::makeDeepCopy ( EcFoundCommon::DeepCopyFlag  copyFlag)
virtual

Make a deep copy of the system and/or shapes.

Parameters
copyFlagIf set to CopySystem, then the system of this stated system will be copied (i.e. unreferenced from other stated systems) but shapes would still be shard. If set to CopyShape, then both the system and shapes will be copied so that this stated system does not share anything (system nor shapes) with another stated system.
virtual const EcShapeStateCacheKeyVector& EcStatedSystem::modifiedShapeKeyVec ( ) const
virtual

gets deformation states - const version gets the vector of the modified shape key

virtual void EcStatedSystem::propagateAttachedManipulatorStates ( EcManipulatorSystemState state,
EcSystemActiveState actState 
) const
virtual

propagate the states (i.e. calculate the base positions and velocities) of the attached manipulators from the given state and set it back to state

virtual void EcStatedSystem::propagateSelfTo ( EcReal  newTime,
EcSystemActiveState pActState = EcNULL 
)
virtual

propagate its own internal state in time. This keeps the same velocity state and integrates the position state using forward Euler.

virtual void EcStatedSystem::propagateSelfTo ( EcReal  newTime,
EcPropagationResultDataVector resultDataVector,
EcSystemActiveState pActState = EcNULL 
)
virtual

propagate its own internal state in time. This keeps the same velocity state and integrates the position state using forward Euler. Diagnostic data is returned. Collisions are not avoided.

virtual void EcStatedSystem::propagateSelfTo ( EcReal  newTime,
EcPropagationResultDataVector resultDataVector,
EcSystemActiveState pActState,
EcU32  collisionAvoidanceMode,
const EcReal collisionBreakthroughThreshold,
const EcU32 bvLevel,
const EcReal precision 
)
virtual

propagate its own internal state in time. This keeps the same velocity state and integrates the position state using forward Euler. Diagnostic data is returned. Collisions are avoided.

virtual void EcStatedSystem::propagateSingleStateBy ( EcU32  index,
const EcVelocityState velocityState,
EcReal  deltaT,
EcPositionState positionState 
) const
virtual

propagate a single state by delta-t. This keeps the same velocity state and integrates the position state using forward Euler. The manipulator number is given by index.

virtual void EcStatedSystem::propagateSingleStateBy ( EcU32  index,
const EcVelocityState velocityState,
EcReal  deltaT,
EcPositionState positionState,
EcPropagationResultData resultData 
) const
virtual

propagate a single state by delta-t. This keeps the same velocity state and integrates the position state using forward Euler. The manipulator number is given by index. Diagnostic data is returned.

virtual void EcStatedSystem::propagateTo ( EcReal  newTime,
EcManipulatorSystemState state,
EcSystemActiveState pActState = EcNULL 
) const
virtual

Propagates the given state in time. This keeps the same velocity state and integrates the position state using forward Euler.

virtual void EcStatedSystem::propagateTo ( EcReal  newTime,
EcManipulatorSystemState state,
EcPropagationResultDataVector resultDataVector,
EcSystemActiveState actState 
) const
virtual

Propagates the given state in time. This keeps the same velocity state and integrates the position state using forward Euler. Diagnostic data is returned. this method does not avoid collisions.

virtual void EcStatedSystem::propagateTo ( EcReal  newTime,
EcManipulatorSystemState state,
EcPropagationResultDataVector resultDataVector,
EcSystemActiveState actState,
EcU32  collisionAvoidanceMode,
const EcReal collisionBreakthroughThreshold,
const EcU32 bvLevel,
const EcReal precision 
) const
virtual

Propagates the given state in time adhering to the specified collision avoidance mode. This keeps the same velocity state and integrates the position state using forward Euler. Diagnostic data is returned

virtual void EcStatedSystem::propagateVelocityAndPositionStateTo ( EcReal  newTime,
EcManipulatorSystemState state,
EcSystemActiveState actState 
) const
virtual

Propagates the given state in time. This ntegrates the velocity and position state using forward Euler. This method does not check for collisions.

virtual EcBoolean EcStatedSystem::replaceLinkKinematics ( EcU32  manipIndex,
const EcString linkLabel,
const EcLinkKinematics newKinematics 
)
virtual

replace the kinematics the link identified by linkLabel in the manipulator given by the manipulator index. Note that if the system is referenced (i.e. there are more than one copies of the same stated system), this method will have to unreference it and make a new copy of the system.

See also
EcManipulatorSystem::replaceLinkKinematics
virtual EcBoolean EcStatedSystem::replaceLinkProperties ( EcU32  manipulatorIndex,
const EcString linkLabel,
const EcManipulatorLink newLink,
EcBoolean  includeShapeContainer = EcFalse 
)
virtual

replace the link properties (link kinematics, mass properties, joint actuator, shape container, etc.) of the link identified by linkLabel with the properties of newLink.

Parameters
[in]manipulatorIndexThe index of the manipulator to which the link belongs.
[in]linkLabelThe string identifier of the link whose properties are to be changed.
[in]newLinkA link whose properties will be used.
[in]includeShapeContainerIf true, the shape container of the link identified by linkLabel will be replaced by the shape container of newLink. Shape container is a special case because of it may be referenced, in which case it needs to be unreferenced. The default is false, i.e. the shape container will not be replaced.
Returns
True if successful or false if linkLabel is invalid.
virtual EcBoolean EcStatedSystem::replaceLinkShape ( EcU32  manipIndex,
const EcString linkLabel,
const EcShape shape,
EcU32  bvhLevel,
EcBoolean  alwaysReplace = EcFalse 
)
virtual

replace the shape of the link identified by linkLabel in the manipulator given by the manipulator index. Note that if the system is referenced (i.e. there are more than one copies of the same stated system), this method will have to unreference it and make a new copy of the system.

See also
EcManipulatorSystem::replaceLinkShape
virtual EcBoolean EcStatedSystem::replaceLinkShape ( EcU32  manipIndex,
const EcU32  linkIndex,
const EcShape shape,
EcU32  bvhLevel,
EcBoolean  alwaysReplace = EcFalse 
)
virtual

replace the shape of the link identified by linkIndex in the manipulator given by the manipulator index. Note that if the system is referenced (i.e. there are more than one copies of the same stated system), this method will have to unreference it and make a new copy of the system.

See also
EcManipulatorSystem::replaceLinkShape
virtual void EcStatedSystem::rightSizeState ( EcManipulatorSystemState state) const
virtual

Extend the state with zeros or contract to a size that agrees with the system size.

Examples:
ecCollisionAvoidanceExample.cpp.
virtual EcBoolean EcStatedSystem::scaleManipulatorBy ( EcU32  manipulatorIndex,
EcReal  scaleFactor 
)
virtual

scale an individual manipulator by the given distance factor scaleFactor 1.0 leaves the manipulator unchanged.

virtual void EcStatedSystem::setBuildShapeLevelAABB ( EcBoolean  buildShapeLevel)
virtual

set whether to build AABB at shape level

virtual void EcStatedSystem::setFromManipulator ( const EcIndividualManipulator manipulator)
virtual

sets all data from a single manipulator. Uses the midpoint between joint limits to set the state positions.

virtual void EcStatedSystem::setFromSystem ( const EcManipulatorSystem system)
virtual

sets all data from a system. Uses the midpoint between joint limits to set the state positions.

Examples:
ecProgrammaticConstructionMain.cpp.
virtual EcBoolean EcStatedSystem::setJointLimit ( EcU32  manipulatorIndex,
const EcString linkLabel,
EcBoolean  isLowerLimit,
EcReal  value 
)
virtual

set the new value for a joint limit

Parameters
[in]manipulatorIndexThe index of the manipulator
[in]linkLabelThe identifying label of the link (joint)
[in]isLowerLimitTrue for a lower limit or false for upper limit
[in]valueThe new value for the joint limit
Returns
True if successful or false if linkLabel is invalid
virtual void EcStatedSystem::setManipulatorCanBeStatic ( EcU32  manipIndex,
EcBoolean  setStatic 
)
virtual

Set the manipulator flag "canBeStatic" to true, and attempt to make the manipulator currently static if the manipultor is attached, not fixed base, or has multiple DOF, it will not be marked static

EcBoolean EcStatedSystem::setNamedFrames ( const EcU32  manIndex,
const EcU32  linkIndex,
const EcNamedFrames namedFrames 
)

set named frames for a manipulator link If EcFoundCommon::VOIDINDEX is used for manIndex then the manipulator system level named frames are set

virtual const EcToken& EcStatedSystem::token ( ) const
virtual

gets the xml token used for writing out.

Implements EcXmlObject.

Member Data Documentation

ecboost::shared_ptr<EcSystemActiveState> EcStatedSystem::m_pStaticSystemActiveState
mutableprotected

a pointer to a utility vector of position states used for static collision detection (i.e. assuming no position control)

Definition at line 923 of file ecStatedSystem.h.


The documentation for this class was generated from the following file: