Actin®  Version 5.2.0
Software for Robotics Simulation and Control
EcSystemSimulation Class Reference

Holds a simulation environment for a stated system and its position control system. More...

#include <ecSysSimulation.h>

Inheritance diagram for EcSystemSimulation:
EcXmlCompoundType EcXmlObject

Public Member Functions

 EcSystemSimulation ()
 default constructor
 
virtual ~EcSystemSimulation ()
 destructor
 
 EcSystemSimulation (const EcSystemSimulation &orig, EcFoundCommon::DeepCopyFlag copyFlag=EcFoundCommon::CopyNone)
 copy constructor
 
EcSystemSimulationoperator= (const EcSystemSimulation &orig)
 assignment operator
 
EcBoolean operator== (const EcSystemSimulation &orig) const
 equality operator
 
virtual EcBoolean mergeWith (const EcSystemSimulation &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
 register 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 EcSystemControlExecutivesystemControlExecutive () const
 gets the system control executive
 
virtual EcSystemControlExecutivesystemControlExecutive ()
 gets the system control executive – non-const
 
virtual void setSystemControlExecutive (const EcSystemControlExecutive &value)
 sets the system control executive
 
virtual const EcStatedSystemstatedSystem () const
 gets the stated system
 
virtual EcStatedSystemstatedSystem ()
 gets the stated system - non-const version
 
virtual void setStatedSystem (const EcStatedSystem &statedSystem)
 sets the stated system
 
virtual const EcVectorupGravity () const
 get the up gravity vector
 
virtual void setUpGravity (const EcVector &upGravity)
 set the up-gravity vector
 
virtual const EcPositionControlContainerpositionControlContainer () const
 gets the position control system container
 
virtual void setPositionControlContainer (const EcPositionControlContainer &positionControlContainer)
 sets the position control system container. This will internally set the stated system of the position control container to controlStatedSystem().
 
virtual void setPositionControlContainerWithState (const EcPositionControlContainer &positionControlContainer)
 sets the position control system container. This will internally set the stated system of the position control container to that of the position control system in positionControlContainer (the argument).
 
virtual const EcPositionControlSystempositionControlSystem () const
 gets the position control system
 
virtual void setPositionControlSystem (const EcPositionControlSystem &positionControlSystem)
 sets the position control system. This will internally set the stated system of the position control system to controlStatedSystem().
 
virtual void setPositionControlSystemWithState (const EcPositionControlSystem &positionControlSystem)
 sets the position control system. This will internally set the stated system of the position control system to that of positionControlSystem (the argument).
 
virtual const EcManipulatorSystemStatepositionControlState () const
 gets the position control state.
 
virtual void setPositionControlState (const EcManipulatorSystemState &positionControlState)
 sets the position control state.
 
virtual EcBoolean externalPositionControl () const
 gets the external-position-control flag
 
virtual void setExternalPositionControl (const EcBoolean value)
 sets the external-position-control flag
 
void externalControlTorqueFlags (EcBooleanVectorVector &flags)
 gets external control torque flags
 
void setExternalControlTorqueFlags (const EcBooleanVectorVector &flags)
 sets the external control torque flags
 
void setExternalControlTorques (const EcManipulatorTorqueVector &controlTorqueVector)
 sets the external control torques
 
void setExternalControlTorque (const EcManipulatorTorque &controlTorque, const EcU32 manipIndex)
 sets external control torque for a single manipulator
 
const EcManipulatorTorqueVectorexternalControlTorques () const
 gets external control torques
 
virtual EcBoolean externalJointTorquesOnly () const
 Indicates whether only external joint torques are used.
 
virtual EcBoolean setFromPositionControlSystem (const EcPositionControlSystem &positionControlSystem, const EcVisualizationParameters &visualizationParameters)
 
virtual void setStatedAndPositionControlSystem (const EcStatedSystem &statedSystem, const EcPositionControlSystem &positionControlSystem)
 
virtual const EcJointControllerSystemContainerjointControllerSystemContainer () const
 gets the joint controller system container
 
virtual void setJointControllerSystemContainer (const EcJointControllerSystemContainer &jointControllerSystemContainer)
 sets the joint controller system container
 
virtual const EcDynamicSimulatorSystemdynamicSimulatorSystem () const
 gets the dynamic simulator system
 
virtual void setDynamicSimulatorSystem (const EcDynamicSimulatorSystem &dynamicSimulatorSystem)
 sets the dynamic simulator system
 
virtual void setManipulatorDynamicallySimulate (const EcU32 &manipIndex, const EcBoolean &value=EcTrue)
 set the dynamic simulator flag on the manipulator level
 
virtual EcBoolean manipulatorDynamicallySimulate (const EcU32 &manipIndex)
 set the dynamic simulator flag on the manipulator level
 
virtual EcReal timeStep () const
 gets the time step
 
virtual void setTimeStep (const EcReal timeStep)
 sets the time step
 
virtual EcU32 maxIterations () const
 gets the maximum number of iterations
 
virtual void setMaxIterations (const EcU32 maxIterations)
 sets the maximum number of iterations
 
virtual EcBoolean dynamicallySimulate () const
 gets the flag specifying dynamic simulation
 
virtual void setDynamicallySimulate (const EcBoolean dynamicallySimulate=EcTrue)
 sets the flag specifying dynamic simulation
 
virtual const EcVisualizationParametersvisualizationParameters () const
 gets the visualization parameters
 
virtual void setVisualizationParameters (const EcVisualizationParameters &visualizationParameters)
 sets the visualization parameters
 
virtual EcU32 randomNumberSeed () const
 gets the random number seet
 
virtual void setRandomNumberSeed (const EcU32 randomNumberSeed)
 sets the random number seet
 
virtual const EcViewerParametersviewerParameters () const
 gets the viewer parameters
 
virtual void setViewerParameters (const EcViewerParameters &viewerParameters)
 sets the viewer parameters
 
virtual const EcManipulatorTorqueVectorlastAppliedTorques () const
 get the last applied torques
 
virtual const EcManipulatorControlInputVectorlastComputedControlInputs () const
 get the last computed control inputs
 
virtual const EcManipulatorEndEffectorPlacementVectordesiredPlacementVector () const
 gets the desired end-effector placements
 
virtual void setDesiredPlacementVector (const EcManipulatorEndEffectorPlacementVector &desiredPlacementVector)
 sets the desired end-effector placements
 
virtual void setDesiredPlacement (const EcManipulatorEndEffectorPlacement &desiredPlacement, const EcU32 manipulatorIndex)
 sets a desired end-effector placement for a manipulator
 
virtual void setDesiredPlacement (EcU32 manipulatorIndex, EcU32 endEffectorIndex, const EcCoordinateSystemTransformation &desiredPlacement)
 sets an individual desired end-effector placement
 
virtual void setDesiredPlacement (EcU32 manipulatorIndex, EcU32 endEffectorIndex, const EcEndEffectorPlacement &desiredPlacement)
 sets an individual desired end-effector placement
 
virtual void setEndEffectorRelativeLinkData (const EcU32 manipulatorIndex, const EcU32 endEffectorIndex, const EcEndEffectorRelativeLinkData &relData)
 sets the relative link data
 
virtual const EcManipulatorEndEffectorVelocityVectordesiredVelocityVector () const
 gets the desired end-effector velocities
 
virtual EcBoolean lookupManipulatorIndexFromLabel (const EcString &label, EcU32 &manipIndex) const
 get the manipulator index from base link label
 
virtual void setDesiredVelocityVector (const EcManipulatorEndEffectorVelocityVector &desiredVelocityVector)
 sets the desired end-effector velocities
 
virtual void setDesiredVelocity (const EcManipulatorEndEffectorVelocity &desiredVelocity, const EcU32 manipulatorIndex)
 sets an individual desired end-effector velocity More...
 
virtual void addDesiredPlacementVector (const EcManipulatorEndEffectorPlacementVector &desiredPlacementVector)
 add desired placement to the end of desired placement in
 
virtual const EcManipulatorEndEffectorPlacementVectoractualPlacementVector () const
 gets the actual end-effector placements
 
virtual void setActualPlacementVector (const EcManipulatorEndEffectorPlacementVector &actualPlacementVector)
 sets the actual end-effector placements
 
virtual EcBoolean setActiveControlDescription (const EcU32 manipulatorIndex, const EcU32 controlDescriptionIndex)
 sets the active control description of a manipulator by index More...
 
virtual EcU32 activeControlDescriptionIndex (const EcU32 manipulatorIndex) const
 gets the index of the active control description of the specified manipulator More...
 
virtual const EcControlExpressionDescriptioncontrolExpressionDescription (const EcU32 manipulatorIndex) const
 gets control expression description
 
virtual void setControlExpressionDescription (const EcControlExpressionDescription &controlExpressionDescription, const EcU32 manipulatorIndex)
 sets control expression description
 
virtual const EcEndEffectorSetendEffectorSet (const EcU32 manipulatorIndex) const
 gets an end effector
 
virtual void setEndEffectorSet (const EcEndEffectorSet &endEffectorSet, const EcU32 manipulatorIndex)
 sets an end effector
 
virtual EcBoolean setEndEffectorSets (const EcU32 manipulatorIndex, const EcEndEffectorSetVector &endEffectorSets)
 sets the end effector sets for a manipulator
 
virtual void resetTime ()
 resets time to zero while keepting the current state
 
virtual void setFromVisualizableStatedSystem (const EcVisualizableStatedSystem &visStatedSystem)
 initialize the entire simulation from a visualizable stated system
 
virtual void getVisualizableStatedSystem (EcVisualizableStatedSystem &visStatedSystem) const
 get the corresponding visualizable stated system
 
virtual const EcManipulatorGraspingModuleVectormanipulatorGraspingModules () const
 gets manipulator grasping module vector
 
virtual void setManipulatorGraspingModules (const EcManipulatorGraspingModuleVector &manipulatorGraspingModules)
 sets manipulator grasping module vector
 
const EcForceControlSystemforceControlSystem () const
 get func for force control system
 
void setForceControlSystem (const EcForceControlSystem &forceControlSystem)
 set func for force control system
 
virtual EcBoolean setActiveForceControlDescription (const EcU32 manipulatorIndex, const EcU32 activeControlDescriptionIndex)
 sets the active force control description of a manipulator by index More...
 
virtual EcBoolean enableForceControllers (const EcU32 manipulatorIndex, const EcU32Vector &controllerIndices, const EcBoolean isOn)
 turn on/off a group of force controllers for a given manipulator
 
virtual void setDesiredForceVector (const EcManipulatorSensorForceVector &desiredForceVec)
 set the desired forces for force control
 
virtual void setMeasuredForceVector (const EcManipulatorSensorForceVector &measuredForceVec)
 set the measured forces for force control
 
virtual EcBoolean calculateState (const EcReal time, EcManipulatorSystemState &state)
 calculate a new manipulator state
 
virtual EcBoolean findAndConvertToReferences ()
 
virtual const EcTokentoken () const EC_OVERRIDE
 gets the xml token used for writing out
 
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 isForceControlOn () const
 gets the is force control on
 
void setIsForceControlOn (const EcBoolean isForceControlOn)
 set is force control on
 
virtual const EcEndEffectorSetVectorguideFrameEndEffectorSetVec () const
 gets Guide Frame EndEffector Set Vector
 
void setGuideFrameEndEffectorSetVec (const EcEndEffectorSetVector &guideFrameEndEffectorSetVec)
 set Guide Frame EndEffector Set Vector
 
virtual void setState (const EcManipulatorSystemState &state)
 sets the state of the system. It also initializes everything.
 
virtual void setCurrentState (const EcManipulatorSystemState &state)
 sets the current state of the system without re-initializing
 
void setSensedState (const EcManipulatorSystemState &state, const EcReal timeStep, const EcBooleanVector &notSetFlags=EcBooleanVector(), const EcBoolean baseOnly=EcFalse)
 feed back the externally sensed position state to the position controller More...
 
virtual void setSensedState (const EcU32 manipIndex, const EcPositionState &posState, const EcReal timeStep, const EcBoolean baseOnly=EcFalse)
 feed back the externally sensed position state of a given manipulator to the position controller More...
 
virtual const EcSystemDataCapturestorageSystemDataCapture () const
 return the system data capture for storage.
 
virtual void setStorageSystemDataCapture (const EcSystemDataCapture &systemDataCapture)
 set the system data capture for storage
 
virtual void captureStorageData () const
 capture the data for storage
 
virtual const EcDisplaySystemDataCaptureVectordisplaySystemDataCaptureVector () const
 return the vector of system data captures for display.
 
virtual void setDisplaySystemDataCaptureVector (const EcDisplaySystemDataCaptureVector &value)
 set the vector of system data captures for display
 
virtual void captureDisplayData () const
 capture the data for display
 
virtual const EcOutputWriterVectoroutputWriterVector () const
 return a vector of writers that write the simulation outputs to different file formats
 
virtual void setOutputWriterVector (const EcOutputWriterVector &outputWriterVector)
 set a vector of writers that write the simulation outputs to different file formats
 
virtual const EcImageSensorVectorimageSensorVector () const
 return the vector of image sensors
 
virtual void setImageSensorVector (const EcImageSensorVector &imageSensorVector)
 set the vector of image sensors
 
virtual const EcPropagationResultDataVectorpropagationResultDataVector () const
 get the propagation results from the control system
 
virtual EcBoolean generateCollisionReport (EcPropagationResultDataVector &collisions) const
 generate a collision report for the state as it currently stands
 
virtual EcBoolean shareStatedSystemWithControl () const
 gets the flag indicating whether or not the simulation should share the stated system with control
 
virtual void setShareStatedSystemWithControl (const EcBoolean value)
 sets the flag indicating whether or not the simulation should share the stated system with control
 
virtual const EcStatedSystemcontrolStatedSystem () const
 gets the stated system for control.
 
virtual void setControlStatedSystem (const EcStatedSystem &statedSystem)
 sets the stated system for control. If shareStatedSystemWithControl is set to true, then this will do nothing since control will use the same stated system with simulation
 
virtual EcBoolean noiseInSimulationFlag () const
 gets the flag indicating whether or not noise is on in the simulation. If it's on, then noise will be introduced to the control torque, the actual position measurements, and the actual velocity measurements.
 
virtual void setNoiseInSimulationFlag (const EcBoolean value)
 sets the noise in simulation flag
 
virtual const EcXmlRealVectorVectorjointTorqueOneSigmas () const
 gets the one sigma values for joint torques for all manipulators
 
virtual void setJointTorqueOneSigmas (const EcXmlRealVectorVector &values)
 sets the one sigma values for joint torques for all manipulators
 
virtual void setJointPositionOneSigmas (const EcXmlRealVectorVector &values)
 sets the one sigma values for joint position sensors for all manipulators
 
virtual void setJointVelocityOneSigmas (const EcXmlRealVectorVector &values)
 sets the one sigma values for joint velocity sensors for all manipulators
 
virtual const EcSystemRandomVariationsystemRandomVariation () const
 gets the system random variation. This is primarily used in Monte Carlo studies.
 
virtual void setSystemRandomVariation (const EcSystemRandomVariation &value)
 sets the system random variation
 
virtual const EcStateRandomVariationstateRandomVariation () const
 gets the state random variation. This is primarily used in Monte Carlo studies.
 
virtual void setStateRandomVariation (const EcStateRandomVariation &value)
 sets the state random variation
 
virtual const EcControlInputConverterContainercontrolInputConverterContainer () const
 gets the container that converts the control torques to control inputs
 
virtual void setControlInputConverterContainer (const EcControlInputConverterContainer &value)
 gets the container that converts the control torques to control inputs
 
virtual EcBoolean useControlTorquesInDynamicSimulation () const
 a flag indicating whether to use control torques in dynamic simulation. If false, control torques will be converted to control inputs and the control inputs will be used in simulation
 
virtual void setUseControlTorquesInDynamicSimulation (const EcBoolean value)
 sets whether to use control torques in dynamic simulation
 
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 ()
 sets isSystemModified to false. Rendering should call this after it's done grabbing new pointers to the system internals.
 
virtual EcBoolean setSelfCollisionMap (const EcManipulatorSelfCollisionLinkMap &map, const EcU32 manipID)
 set the self collisin map for manipulator manipID
 
virtual void setDynamicSystemTimeStep (const EcReal timestep)
 pass through to set the timestep in the dynamic simulator system
 
virtual EcReal dynamicSystemTimeStep () const
 pass through to get the timestep in the dynamic simulator system
 
virtual EcInt32 deleteManipulator (const EcString &manipLabel)
 delete a manipulator and corresponding data (e.g. position and velocity states, end-effectors, etc.) More...
 
virtual EcBoolean deleteManipulator (const EcU32 manIndex)
 
virtual EcU32 addManipulator (const EcIndividualManipulator &manip, const EcPositionState &position, const EcBaseManipulatorJointController *jointController=EcNULL)
 add a manipulator and corresponding data (e.g. position and velocity states, end-effectors, etc.) More...
 
virtual EcU32 cloneManipulator (EcU32 manipIndex)
 clone a manipulator and corresponding data (e.g. position and velocity states, end-effectors, etc.)
 
virtual EcU32 copyManipulator (EcU32 manipIndex)
 copy a manipulator and corresponding data (e.g. position and velocity states, end-effectors, etc.)
 
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 changeManipulatorLabel (const EcString &manipLabel, const EcString &newLabel)
 change manipulator label
 
virtual EcBoolean addAvoidanceRegion (const EcShape &shape, const EcString &regionName, const EcCoordinateSystemTransformation &position, const EcDataMap &color=EcSurfaceColorFactory::boundingColor())
 insert an avoidance region into the system
 
virtual EcU32 activePositionControlMethodIndex (const EcU32 manipIndex) const
 get the index of the active control method
 
virtual EcBoolean setActivePositionControlMethod (const EcU32 manipIndex, const EcU32 methodIndex)
 set the active control method
 
virtual EcU32 activeEndEffectorSetIndex (const EcU32 manipIndex) const
 get the index of the active end-effector set
 
virtual EcBoolean setActiveEndEffectorSet (const EcU32 manipIndex, const EcU32 eeIndex)
 set the active control method
 
EcBoolean setActiveEndEffectorIndex (const EcU32 manipulatorIndex, const EcU32 index)
 
EcBoolean setJointControlEndEffectorSetAndPlacement (const EcU32 manipIndex, const EcEndEffectorPlacement &desiredPlacement)
 set the active end effector set to joint control and set desired placement
 
virtual EcBoolean exchangeManipulator (const EcU32 manipIndex, const EcSystemSimulation &other, const EcU32 otherManipIndex)
 exchange the manipulator (and its controller) at the specified index with one from another simulation
 
virtual EcBoolean setBaseSpeedFactor (const EcU32 manipIndex, const EcReal value)
 
virtual EcBoolean setSpeedFactor (const EcU32 manipIndex, const EcReal speedFactor)
 
virtual EcBoolean setBaseAccelerationFactor (const EcU32 manipIndex, const EcReal value)
 
virtual EcBoolean setAccelerationFactor (const EcU32 manipIndex, const EcReal value)
 
virtual EcBoolean setProfiledPositionEndEffectors (const EcU32 manipIndex, const EcU32Vector &indices)
 
virtual void setAttachmentMap (const EcManipulatorAttachmentMap &value)
 set the manipulator attachment map
 
virtual void setDynamicCollisionExclusionMap (const EcSystemCollisionExclusionMap &value)
 set the dynamic collision exclusion map
 
virtual void setStaticCollisionExclusionMap (const EcSystemCollisionExclusionMap &value)
 set the static collision exclusion map
 
virtual EcBoolean setControlMode (const EcU32 manipIndex, const EcU32 mode)
 Sets the control mode of an end-effector by index. More...
 
virtual void setExternalJointTorquesOnly (const EcBoolean extTorquesOnly)
 Set whether only external joint torques are used (bypass joint control system)
 
virtual EcU32 activeManipulatorIndex () const
 get the index of the active manipulator (i.e. under control of user interaction)
 
virtual EcBoolean setActiveManipulatorIndex (EcU32 value)
 set the index of the active manipulator (i.e. under control of user interaction)
 
virtual EcBoolean setCollisionStop (EcU32 manipIndex, EcBoolean value)
 turn on/off stop at collision in the control system for a given manipulator
 
virtual EcBoolean setHardStop (const EcU32 manipIndex)
 this will force the velocity of the given manipulator to zero and abruptly stop at its current position More...
 
- 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 EcSystemSimulation nullObject ()
 get a null object
 

Protected Member Functions

virtual void initializeComponents ()
 initializes member variables
 
virtual void initializeControlComponents ()
 initializes member variables related to control
 
virtual EcBoolean dynamicallySimulateOneStep (const EcReal timeStep)
 dynamically simulate one step forward.
 
virtual void limitControlTorques (EcManipulatorTorqueVector &manipTorqueVector) const
 limit control torques to the physical limits
 
virtual EcBoolean calcForcePlacement (const EcReal time)
 calculate force control placement and set the position
 
virtual void updatePositionControlState (const EcReal timeStep)
 update the position control state using the dynamic simulation
 
virtual void addNoiseToControlTorques (EcManipulatorTorqueVector &manipTorqueVector, const EcXmlRealVectorVector &oneSigmasVector) const
 add noise to control torques
 
virtual void registerComponentCreators (EcXmlReader &stream)
 register the component creators of some classes that have not been registered (most likely because registering those component creators may cause cyclic dependency) to the reader stream so the components can be read in properly.
 
virtual void addComponents (const EcBaseManipulatorJointController *jointController=EcNULL)
 add necessary components
 
virtual void deleteComponents (const EcU32 manipIndex)
 delete components for a manipulator
 
virtual EcU32 addManipulator (EcU32 manipIndex, EcBoolean bClone)
 
- 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

EcSystemControlExecutive m_SystemControlExecutive
 the system control executive
 
EcForceControlSystem m_ForceControlSystem
 the force control system
 
EcJointControllerSystemContainer m_JointControllerSystemContainer
 the joint controller system
 
EcDynamicSimulatorSystem m_DynamicSimulatorSystem
 the dynamic simulator
 
EcXmlReal m_TimeStep
 the time step for dynamic simulation
 
EcXmlU32 m_MaxIterations
 the maximum number of iterations per call
 
EcXmlBoolean m_DynamicallySimulate
 a flag indicating whether or not to dynamically simulate
 
EcVisualizationParameters m_VisualizationParameters
 visualization parameters
 
EcViewerParameters m_ViewerParameters
 viewer parameters
 
EcManipulatorGraspingModuleVector m_ManipulatorGraspingModules
 grasping container
 
EcXmlU32 m_RandomNumberSeed
 a random number seed
 
EcSystemDataCapture m_StorageSystemDataCapture
 an object used to capture and store system data
 
EcDisplaySystemDataCaptureVector m_vDisplaySystemDataCapture
 to configure multiple data capture objects for display (plotting)
 
EcOutputWriterVector m_vOutputWriters
 write the simulation outputs to different file formats
 
EcImageSensorVector m_vImageSensors
 a vector of image sensors
 
EcXmlBoolean m_NoiseInSimulationFlag
 the flag indicating whether or not noise is on in the simulation
 
EcXmlRealVectorVector m_vJointTorqueOneSigmas
 the one sigma values for joint torque noise
 
EcSystemRandomVariation m_SystemRandomVariation
 the system random variation
 
EcStateRandomVariation m_StateRandomVariation
 the state random variation
 
EcControlInputConverterContainer m_ControlInputConverterContainer
 container that converts control torques to control inputs
 
EcXmlBoolean m_UseControlTorques
 a flag indicating whether to use control torques in dynamic simulation
 
EcStatedSystem m_StatedSystem
 the stated system
 
EcPositionControlContainer m_PositionControlContainer
 the position control system
 
EcStatedSystem m_ControlStatedSystem
 the stated system for control
 
EcXmlBoolean m_ShareStatedSystemWithControl
 a flag indicating whether or not the simulation should share the stated system with control
 
EcManipulatorSystemState m_PositionControlState
 holds the latest result from the position control system
 
EcManipulatorTorqueVector m_ManipulatorTorques
 holds the applied torques on the manipulator
 
EcManipulatorControlInputVector m_ManipulatorControlInputs
 holds the control inputs
 
EcBoolean m_ExternalJointTorquesOnly
 Indicates only external joint torques are used (no joint control necessary)
 
EcManipulatorTorqueVector m_ExternalControlTorques
 holds the external control torques on the manipulator
 
EcReal m_DynamicSimulationTime
 a variable to hold the dynamic simulation time
 
EcBooleanVector m_UtilityEmptyBooleanVector
 a utility vector for boolean flags
 
- 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

- Public Types inherited from EcXmlCompoundType
enum  {
  READONLYCOMPONENT = 0,
  READONLYATTRIBUTE
}
 special-descriptor codes More...
 
- 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 simulation environment for a stated system and its position control system.

Holds a simulation environment for a stated system and its position control system.

Examples:
ecCameraViewMain.cpp, ecPathPlanningMain.cpp, ecProfilingMain.cpp, ecProgrammaticConstructionMain.cpp, ecQuickStartKinematicsMain.cpp, and ecQuickStartMain.cpp.

Definition at line 36 of file ecSysSimulation.h.

Member Function Documentation

virtual EcU32 EcSystemSimulation::activeControlDescriptionIndex ( const EcU32  manipulatorIndex) const
virtual

gets the index of the active control description of the specified manipulator

Parameters
[in]manipulatorIndexThe index of the manipulator in query.
Returns
The index of the active control description of the specified manipulator.
virtual EcU32 EcSystemSimulation::addManipulator ( const EcIndividualManipulator manip,
const EcPositionState position,
const EcBaseManipulatorJointController jointController = EcNULL 
)
virtual

add a manipulator and corresponding data (e.g. position and velocity states, end-effectors, etc.)

Returns
The index of the newly added manipulator.
virtual EcU32 EcSystemSimulation::addManipulator ( EcU32  manipIndex,
EcBoolean  bClone 
)
protectedvirtual

This method creates a new manipulator similar to manipIndex, if bClone is True, it creates a reference to the source manipulator identified by manipIndex, else, it does not create a reference but creates a deep copy of the source manipulator,

See also
EcManipulatorReferenceDescription
virtual EcInt32 EcSystemSimulation::deleteManipulator ( const EcString manipLabel)
virtual

delete a manipulator and corresponding data (e.g. position and velocity states, end-effectors, etc.)

Parameters
[in]manipLabelThe string label of the manipulator to 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 EcSystemSimulation::deleteManipulator ( const EcU32  manIndex)
virtual

delete a manipulator and corresponding data (e.g. position and velocity states, end-effectors, etc.)

Parameters
[in]manIndexThe manipulator index to delete.
Returns
EcBoolean Success or failure of the command.
virtual EcBoolean EcSystemSimulation::findAndConvertToReferences ( )
virtual

find and convert explicit manipulator link descriptions to references where possible

virtual EcBoolean EcSystemSimulation::setAccelerationFactor ( const EcU32  manipIndex,
const EcReal  value 
)
virtual

sets the acceleration factor of the controller for the manipulator specified by manipIndex. Returns false if manipIndex is invalid or true otherwise.

See also
EcVelocityController::setAccelerationFactor
virtual EcBoolean EcSystemSimulation::setActiveControlDescription ( const EcU32  manipulatorIndex,
const EcU32  controlDescriptionIndex 
)
virtual

sets the active control description of a manipulator by index

Parameters
[in]manipulatorIndexThe index of the manipulator to which the control descriptions will be set.
[in]controlDescriptionIndexThe index of the active control description to be set.
Returns
True if successful or false if either manipulatorIndex or activeControlDescriptionIndex is out of range.
EcBoolean EcSystemSimulation::setActiveEndEffectorIndex ( const EcU32  manipulatorIndex,
const EcU32  index 
)

sets gets the index of the active end-effector for the active EE set of a manipulator by index

Parameters
[in]manipIndexThe index of the manipulator to which the active end-effector set will be set.
[in]eeIndexThe index of the active end-effector to be set.
Returns
True if successful or false if either manipulatorIndex or index is out of range.
virtual EcBoolean EcSystemSimulation::setActiveForceControlDescription ( const EcU32  manipulatorIndex,
const EcU32  activeControlDescriptionIndex 
)
virtual

sets the active force control description of a manipulator by index

Parameters
[in]manipulatorIndexThe index of the manipulator to which the force control description will be set.
[in]activeControlDescriptionIndexThe index of the active control description to be set.
Returns
True if successful or false if either manipulatorIndex or activeControlDescriptionIndex is out of range.
virtual EcBoolean EcSystemSimulation::setBaseAccelerationFactor ( const EcU32  manipIndex,
const EcReal  value 
)
virtual

sets the base acceleration factor of the controller for the manipulator specified by manipIndex. Returns false if manipIndex is invalid or true otherwise.

See also
EcVelocityController::setAccelerationFactor
virtual EcBoolean EcSystemSimulation::setBaseSpeedFactor ( const EcU32  manipIndex,
const EcReal  value 
)
virtual

sets the base speed factor of the controller for the manipulator specified by manipIndex. Returns false if manipIndex is invalid or true otherwise.

See also
EcVelocityController::setBaseSpeedFactor
virtual EcBoolean EcSystemSimulation::setControlMode ( const EcU32  manipIndex,
const EcU32  mode 
)
virtual

Sets the control mode of an end-effector by index.

Parameters
[in]manipIndexThe index of the manipulator to which the control mode will be set.
[in]eeSetIndexthe end-effector set index
[in]eeIndexthe end-effector index
[in]modeThe control mode (EcEndEffector::ControlMode) to be set.
Returns
True if successful or false if an index is out of range.
See also
EcVelocityController::setControlMode
virtual void EcSystemSimulation::setDesiredVelocity ( const EcManipulatorEndEffectorVelocity desiredVelocity,
const EcU32  manipulatorIndex 
)
virtual

sets an individual desired end-effector velocity

virtual EcBoolean EcSystemSimulation::setFromPositionControlSystem ( const EcPositionControlSystem positionControlSystem,
const EcVisualizationParameters visualizationParameters 
)
virtual

initialize the entire simulation from a position control system Note that the pointer to the stated system in positionControlSystem must point to a valid stated system

Examples:
ecProgrammaticConstructionMain.cpp, and ecQuickStartMain.cpp.
virtual EcBoolean EcSystemSimulation::setHardStop ( const EcU32  manipIndex)
virtual

this will force the velocity of the given manipulator to zero and abruptly stop at its current position

virtual EcBoolean EcSystemSimulation::setProfiledPositionEndEffectors ( const EcU32  manipIndex,
const EcU32Vector indices 
)
virtual

sets some end-effectors to follow profiled trajectory for the manipulator specified by manipIndex. If indices is not empty, it will temporarily turn on ignore time step so that profiled trajetory following works correctly. Returns false if manipIndex is invalid or true otherwise. See EcPositionController::setProfiledPositionEndEffectors for details.

void EcSystemSimulation::setSensedState ( const EcManipulatorSystemState state,
const EcReal  timeStep,
const EcBooleanVector notSetFlags = EcBooleanVector(),
const EcBoolean  baseOnly = EcFalse 
)

feed back the externally sensed position state to the position controller

Parameters
[in]stateThe sensed state to be fed back.
[in]timeStepThe time step of how frequently this method is called.
[in]notSetFlagsThe flags indicating which manipulator states will not be fed back. If this vector is empty, then all the states will be fed back.
[in]baseOnlyIf true only the sensed bases will be fed back.
virtual void EcSystemSimulation::setSensedState ( const EcU32  manipIndex,
const EcPositionState posState,
const EcReal  timeStep,
const EcBoolean  baseOnly = EcFalse 
)
virtual

feed back the externally sensed position state of a given manipulator to the position controller

Parameters
[in]manipIndexThe index of the manipulator for which the sensed state will be fed back
[in]posStateThe sensed position state to be fed back.
[in]timeStepThe time step of how frequently this method is called.
[in]baseOnlyIf true only the sensed base will be fed back.
virtual EcBoolean EcSystemSimulation::setSpeedFactor ( const EcU32  manipIndex,
const EcReal  speedFactor 
)
virtual

sets the speed factor of the controller for the manipulator specified by manipIndex. Returns false if manipIndex is invalid or true otherwise.

See also
EcVelocityController::setSpeedFactor
virtual void EcSystemSimulation::setStatedAndPositionControlSystem ( const EcStatedSystem statedSystem,
const EcPositionControlSystem positionControlSystem 
)
virtual

sets the stated system and position control system This should always be used to initially configure these components.


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.