Actin®  Version 5.1.0
Software for Robotics Simulation and Control
Actin Plugin API

The Actin Plugin API

The plugin API is designed to provide extensibility within Actin without having to change the basic framework. The Ec::Plugin and Ec::PluginGUI classes has been designed to provide hooks into the simulation and user interface framework to customize and tailor behavior to suit different needs. External developers can write a Plugin based off of this class without any inherent knowledge of the Actin toolkit. Plugins enable the Actin Viewer and select applications to be extended through a DLL loadable during run-time.

Actin Plugins

Four methods define the API to the plugins as shown in Table 1. The methods, Ec::Plugin::initState() and Ec::Plugin::update(), hold examples on how to pass data between the simulation and the plugin. Text Box 1 contains a code snippet for getting joint commands from the simulation for use in the plugin. The next section shows the complete list of accessible simulation parameters and the methods available for getting and setting simulation parameters.

Ec::Plugin core methods

Method Description
Ec::Plugin::init This is a one-time initialization called right after the constructor. It can be used for memory allocation or other one-time settings on startup.
Ec::Plugin::reset This is called whenever a simulation file is unloaded or when loading in a new simulation file.
Ec::Plugin::initState This is called after each new data file is loaded into the viewer. This enables data to be taken from hardware and used to initialize the simulation. It takes as input a constant reference to the simulation.
Ec::Plugin::update This is called at the simulation rate or a specified rate as set in m_UpdatePeriodInMs. This parameter can be set in the constructor or init() call. It takes as input the simulation time.

There are several member variables available to the plugins as defined in the table below.

Ec::Plugin data memebers
Name Definition
Ec::Plugin::m_Name Name of the plugin. This is by the EC_PLUGIN_STUB(cls, traits) or EC_PLUGIN_STUB_DEFAULT(cls) macro.
Ec::Plugin::m_PluginTraits Describes the capabilities of this plugin. The traits options are defined by Ec::Plugin::PluginTraitsEnum and set by the EC_PLUGIN_STUB(cls, traits) macro in the plugin's implementation (.cpp) file.
Ec::Plugin::m_UpdatePeriodInMs Dictates how often the plugin gets updates. The default is zero which runs the plugin at the simulation rate. This variable is typically set in the constructor or Ec::Plugin::init() methods
Ec::Plugin::m_RequiredPlugins List of plugins that this plugin depends on. This ensures that those plugins are loaded first.

Parameter IO Template API

Plugins can access and modify simulation parameters through Ec::Plugin::setParam, Ec::Plugin::getParam, Ec::Plugin::param, and Ec::Plugin::paramPtr template methods. These four template methods are shown in the sections below. Parameters contained in Ec::ParamTypeEnum can be used as the prm template parameter to the plugin API methods. These parameters are listed in the Table below and all template method specializations are documented in the Detailed Parameter Descriptions section.

Ec::Plugin::setParam Template Method

The Ec::Plugin::setParam template method has three prototypes that can be used to set simulation properties and parameters by value at the system, manipulator, and link level.

The arguments include:

Argument Description
const ParamType& value A class object defining the value type to be set. Note that ParamType is a template parameter which is implictly determined.
const EcU32 manipulatorIndex An unsigned integer that defines the index of the manipulator which is being modified
const EcU32 subIndex An unsigned integer that defines the index of a child element to a manipulator such as a link or motion constraint "end-effector" set.
const EcU32 subSubIndex An unsigned integer that defines the index of a child element to a direct child of a manipulator such as motion constraint "end-effector" or tool offset.
//------------------------------------------------------------
// setParam returns true if the parameter was successfully set
//------------------------------------------------------------
EcBoolean Ec::Plugin::setParam(const ParamType& value);
EcBoolean Ec::Plugin::setParam(const ParamType& value, const EcU32 manipulatorIndex);
EcBoolean Ec::Plugin::setParam(const ParamType& value, const EcU32 manipulatorIndex, const EcU32 subIndex);
EcBoolean Ec::Plugin::setParam(const ParamType& value, const EcU32 manipulatorIndex, const EcU32 subIndex, const EcU32 subSubIndex);
The Ec::Plugin::setParam template method prototypes

Ec::Plugin::getParam Template Method

The Ec::Plugin::getParam template method has four prototypes that can be used to get simulation properties and parameters by value at the system, manipulator, and link level.

The arguments include:

Argument Description
const ParamType& value A class object defining the value type retrieved. Note that ParamType is a template parameter which is implictly determined.
const EcU32 manipulatorIndex An unsigned integer that defines the index of the manipulator which is being modified.
const EcU32 subIndex An unsigned integer that defines the index of a child element to a manipulator such as a link or motion constraint "end-effector" set.
const EcU32 subSubIndex An unsigned integrer that defines the index of a child element to a direct child of a manipulator such as motion constraint "end-effector" or tool offset.
const EcString& identifier A string identifier that can be used to access an object in the system.
//------------------------------------------------------------
// getParam returns true if the parameter was successfully retrieved
//------------------------------------------------------------
EcBoolean Ec::Plugin::getParam(ParamType& value) const;
EcBoolean Ec::Plugin::getParam(ParamType& value, const EcU32 manipulatorIndex) const;
EcBoolean Ec::Plugin::getParam(ParamType& value, const EcU32 manipulatorIndex, const EcU32 subIndex) const;
EcBoolean Ec::Plugin::getParam(ParamType& value, const EcU32 manipulatorIndex, const EcU32 subIndex, const EcU32 subSubIndex) const;
EcBoolean Ec::Plugin::getParam(const EcString& manipIdentifier, ParamType& value) const;
The Ec::Plugin::getParam template method prototypes

Ec::Plugin::param Template Method

//------------------------------------------------------------
// param retrieves a copy of the parameter
//------------------------------------------------------------
const ParamType Ec::Plugin::param() const;
The Ec::Plugin::param template method prototype

Ec::Plugin::paramPtr Template Method

//------------------------------------------------------------
// paramPtr retrieves a constant pointer to the parameter object
//------------------------------------------------------------
const ParamType* Ec::Plugin::paramPtr() const;
The Ec::Plugin::paramPtr template method prototype
Note
To prevent race conditions, the Simulation Mutex should be locked prior to accessing a pointer from a Ec::Plugin::paramPtr method. The Simulation Mutex must be released immediately after the pointer is no longer needed.
Warning
To prevent deadlock with other plugin threads DO NOT call any Ec::Plugin::param, Ec::Plugin::getParam, or Ec::Plugin::setParam methods within the scope of the Simulation Mutex lock. Only Ec::Plugin::paramPtr methods may be called within the scope of the lock.

Example Usage

This section provides a few examples for using the Plugin API templated methods. The code block below shows an example of getting the actual end-effector placement for a manipulator and then setting it as the desired placement in order to hold the manipulator at its current position.

// Get a pointer to myPlugin
Ec::Plugin* pPlugin = Ec::Plugin::getPlugin("myPlugin");
// Check that the pointer is valid
if(!pPlugin)
{
return;
}
// Set the manipulator index
const EcU32 manipulatorIndex = 0;
// Create an object for actual end-effector placement
// This method will retrieve the actual end-effector placement for the manipulator
if( pPlugin->getParam<Ec::ActualEndEffector>(manipulatorIndex, actualPlacement) )
{
// This method will set the desired end-effector placement to the current actual placement
// to stop the manipulator at its current end effector positions.
pPlugin->setParam<Ec::DesiredEndEffector>(manipulatorIndex, actualPlacement);
}

The example below shows proper usage of the Ec::Plugin::getParam method to obtain a lock on the simulation mutex prior to accessing the control system data through the Ec::Plugin::paramPtr method.

// Get a pointer to myPlugin
Ec::Plugin* pPlugin = Ec::Plugin::getPlugin("myPlugin");
// Check that the plugin pointer is valid
if(pPlugin)
{
// Create a shared lock. This allows other readers to lock the mutex simultaniously
// Get a lock on the simulation mutex before calling paramPtr
if(pPlugin->getParam<Ec::SimulationMutex>(lock))
{
// Get a pointer to the position control container
// Retrieve data from pControlContainer as needed.
// The simulation mutex will be unlocked when the lock goes out of scope.
}
}
Example usage of the Ec::Plugin::getParam and Ec::Plugin::paramPtr for the Ec::SimulationMutex and Ec::ControlSystem paramter types

List of Accessible Parameters

The plugins can access and modify many of the simulation parameters through the Ec::Plugin::getParam and Ec::Plugin::setParam template methods. All parameters that can be set or get through these methods is defined by the Ec::ParamTypeEnum enum in ecIOParams.h.

The following table describes the various simulation parameters that can be read/modified using the get,set methods of the IOBuffer.
Some of the notations used in the table are:

  • A * indicates that it should be replaced by the Parameter name for e.g ActiveState or AttachmentMap
  • There are five different types of methods available for a parameter
    • G: implies it is a get method, that allows the value of simulation parameter to be read. Usually the last parameter in the list will be used to get the value back and that should be passed as a reference type
    • S: implies it is set method, it allows the value of simulation parameter to be modfied. Usually the last parameter in the list will be used for this and it should a const reference
    • Both the get and set methods return a boolean value indicating whether the call was successful or not. If the input parameters are incorrect for instance an incorrect manipIndex, the function will return false
    • P: implies there is version of the get method available, where the simulation parameter value is returned back
    • Pr: implies that there is a version of the get method available where the simulation parameter is returned as a const pointer
    • B: implies that there is a version of the get method available where the simulation parameter is returned as a boost shared pointer
    • MC: Motion Constraint
    • MCI: Motion Constraint Index
    • MCS: Motion Constraint Set
    • MCSI Motion Constraint Set Index
Ec::Plugin templated method parameter types

Method
Types
Template Parameters Function Parameters Description
AccelerationFactor
SG <*, EcReal> (EcU32 manipIndex, EcReal accelerationFactor) get/set acceleration factor for a manipulator's velocity controller
SG <*, EcReal> (EcU32 manipIndex, EcU32 eeSetIndex, EcU32 eeIndex, EcReal accelerationFactor)

get/set acceleration factor for motion constraint of a manipulator

ActiveState
SG <*, EcManipulatorActiveState> (const EcU32 manipIndex, EcManipulatorActiveState)get/set active state for a manipulator
SGP <*, EcManipulatorActiveStateVector> (EcManipulatorActiveStateVector& value)get/set active state vector
GPrB <*, EcSystemActiveState> (EcSystemActiveState& value)

gets the active state of the system

ActualEndEffector
G <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 mcIndex, EcCoordinateSystemTransformation& value) gets the true coordinates of MC as a EcCoordinateSystemTransformation for a specific mcIndex of a manipulator specified by manipIndex
G <*, EcManipulatorEndEffectorPlacement> (const EcU32 manipIndex, const EcU32 mcIndex, EcEndEffectorPlacement& value) gets the true location of MC as a EcEndEffectorPlacement for a specific mcIndex of a manipulator specified by manipIndex
G <*, EcVector> (const EcU32 manipIndex, const EcU32 mcIndex, EcVector& value)gets the true placement of MC as a EcVector for a specific mcIndex of a manipulator specified by manipIndex
G <*, EcOrientation> (const EcU32 manipIndex, const EcU32 eeIndex, EcOrientation& value)gets the orientation of MC as a EcOrientation for a specific mcIndex of a manipulator specified by manipIndex
GP <*, EcManipulatorEndEffectorPlacementVector> (EcManipulatorEndEffectorPlacementVector)gets/returns the true placement of MC as a EcManipulatorEndEffectorPlacementVector
G <*, EcManipulatorEndEffectorPlacement> (const EcU32 manipIndex, const EcU32 mcSetIndex, EcManipulatorEndEffectorPlacement& value)gets the current placement of a specific mcSetIndex of a manipulator as a EcManipulatorEndEffectorPlacement datatype
G <*, EcReal> (const EcU32 manipIndex, const EcU32 mcIndex, EcReal& value)

gets the scalar placement of a specific MC with one degree of constraint of a manipulator

ActualVelocity
G <*, EcManipulatorEndEffectorVelocity> (const EcU32 manipIndex, EcManipulatorEndEffectorVelocity& value) gets the actual MC velocities for a manipulator
G <*, EcRealVector> (const EcU32 manipIndex, const EcU32 mcIndex, EcRealVector& value)

gets the actual MC velocity for a specific mcIndex of a manipulator specified by manipIndex

AntiCollision
SG <*, EcBoolean> (const EcU32 manIndex, EcBoolean& antiCollStatus)

Turn on/off anti-collision in control system for a manipulator

AttachmentMap
SG <*, EcManipulatorAttachmentMap> (EcManipulatorAttachmentMap& value) get/set the attachment map
S <*, EcManipulatorAttachmentChange> (const EcManipulatorAttachmentChange& value)

set the EcManipulatorAttachmentChange for the active manipulator

Base
SG <*, EcCoordinateSystemTransformationVector> (EcCoordinateSystemTransformationVector &value) get/set the coordinates of base for all manipulator's in the system
SG <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, EcCoordinateSystemTransformation& value) get/set the coordinates of base of a manipulator
SG <*, EcVector> (const EcU32 manipIndex, EcVector& value) get/set the coordinates of base of a manipulator as a EcVector datatype
SG <*, EcOrientation> (const EcU32 manipIndex, EcOrientation& value)

get/set the coordinates of base of a manipulator given as a EcOrientation datatype

BaseAccelerationFactor
SG <*, EcReal> (const EcU32 manipIndex, EcReal& value)

get/set Base acceleration factor for a manipulator

BaseSpeedFactor
SG <*, EcReal> (const EcU32 manipIndex, EcReal& value)

get/set the Base speed factor for a manipulator

BaseVelocity
SG <*, EcGeneralVelocity> (const EcU32 manipIndex, EcGeneralVelocity &value)

get/set the Base velocity for a manipulator

CollisionExclusionMap
SG <*, EcSystemCollisionExclusionMap> (EcSystemCollisionExclusionMap& value) get/set the Dynamic or runtime collision exclusion map for the system
SG <*, EcManipulatorSelfCollisionLinkMap> (const EcU32 manIndex, EcManipulatorSelfCollisionLinkMap& value)

get/set the self collision map for a manipulator

CollisionPriority
SG <*, EcAntiCollisionPriorityList> (EcAntiCollisionPriorityList& value)

get/set the EcAntiCollisionPriorityList for the system

CollisionStop
S <*, EcBoolean> (const EcU32 manipIndex, EcBoolean& value)

Turn on/off "stop at collision" property for a manipulator. If set, on collision the manipulator stops moving further

CalculationTime
P <*, EcReal> ()

returns the Time taken to compute a timestep

ControlDescriptor
SG <*, EcU32> (const EcU32 manipIndex, EcU32& cdIdex) get/set the active Control descriptor specified by the cdIndex to be used/being used by a manipulator
G <*, EcStringVector> (const EcU32 manipIndex, EcStringVector& value)

get all the names/labels of Control descriptors available for a manipulator as a EcStringVector

ControlMethod
SG <*, EcU32> (const EcU32 manipIndex, EcU32& value) get/set the active "Position Control Method" to be used for a manipulator
G <*, EcStringVector> (const EcU32 manipIndex, EcStringVector& value)

get the registered token names of all available "Position Control Methods" for a manipulator

ControlMode
S <*, EcU32> (const EcU32 manipIndex, EcU32 controlMode) set the Control mode to be used for a manipulator
G <*, EcU32Vector> (const EcU32 manipIndex, EcU32Vector& value) get all the available Control modes for a manipulator
SG <*, EcU32> (const EcU32 manipIndex, const EcU32 mcIndex, EcU32& controlMode) get/set the Control mode to be used for the MC of the active MCS for a manipulator
SG <*, EcU32> (const EcU32 manipIndex, const EcU32 mcSetIndex, const EcU32 mcIndex, EcU32& controlMode)

get/set the Control mode to be used for the specified MC of the specified MCS for a manipulator

ControlSystem
SGPrB <*, EcForceControlSystem> (EcForceControlSystem& value) get/set the force conrol system to be used. This method is also supported in a form where a shared pointer to the EcForceControlSystm is returned.
SGPr <*, EcPositionControlContainer> (EcPositionControlContainer& value) get/set the EcPositionControlContainer to be used.
SGPrB <*, EcPositionControlSystem> const EcPositionControlSystem& value) get/set the EcPositionControlSystem to be used.This is also supported in a form (paramPtr) where a const pointer to EcPositionControlSystem is returned or paramScopedPtr where a boost scoped pointer is returned
SGP <*, EcBooean> (EcBoolean& value) Turn the position control on/off for all manipulators in the system
SG <*, EcBooean>(const EcU32 manipIndex, EcBoolean& value)

Turn the position control on/off for a manipulator

DataMap
SG <*, EcDataMap> (EcDataMap& value) get/set the Custom data to exchange among plugins
SG <*, EcReal> (const EcString& key, EcReal& value) get/set a EcReal value for a particular key in the data map
SG <*, EcXmlRealVector> (const EcString& key, EcXmlRealVector& value) get/set a EcXmlRealVector value for a particular key in the data map

We can get/set values of different data types for a particular key in the data map. The above two lines describe variations of the method to set a EcReal value or EcXmlRealVector value. The other supported data types are: EcU32, EcXmlU32Vector, EcString

DesiredEndEffector
SGP <*, EcManipulatorEndEffectorPlacementVector> (EcManipulatorEndEffectorPlacementVector& value) get/set the desired placement of the current active MC as a EcManipulatorEndEffectorPlacementVector
SG <*, EcManipulatorEndEffectorPlacement> (const EcU32 manipIndex, EcManipulatorEndEffectorPlacement& value) get/set the desired placement of active MC of a manipulator as a EcManipulatorEndEffectorPlacement.
This method is also available where we can get the placement as a EcRealVector
S <*, EcManipulatorEndEffectorPlacement> (const EcU32 manipIndex, const EcU32 mcIndex, EcManipulatorEndEffectorPlacement& value) set the desired placement of a specific MC of a manipulator as a EcManipulatorEndEffectorPlacement
SG <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 mcIndex, EcCoordinateSystemTransformation& value) get/set the desired placement of a specific MC of a manipulator as a EcCoordinateSystemTransformation.
This method is also available where we can get the placement as a EcEndEffectorPlacement, EcVector, EcOrientation
SG <*, EcReal> (const EcU32 manipIndex, const EcU32 mcIndex, EcReal& value) Specialization for DesiredEndEffector to handle linear constraint EEs, It will take the incoming value as the value of Z component and
assume a value of 0 for X and Y component while setting, and in the get method, the translation of the Z component is returned
S <*, ParamTypeEnum>

can be used to set the desired MC placement to actual placement of the MC in one call

DesiredEndEffectorRelative
S <*, EcEndEffectorPlacement> (const EcU32 manIndex, const EcU32 eeSetIndex, const EcU32 eeIndex, const EcEndEffectorPlacement& offset)

set the relative desired placement of MC of the specified MCS and MC of a manipulator

DesiredForce
SGP <*, EcManipulatorSensorForceVector> (EcManipulatorSensorForceVector& value) get/set the DesiredForce for all the manipulators
SG <*, EcManipulatorSensorForce> (const EcU32 manIndex, EcManipulatorSensorForce& value)

get/set the DesiredForce for a manipulator

DesiredJointControlEndEffector
S <*, EcEndEffectorPlacement> (const EcU32 manipIndex, const EcEndEffectorPlacement& value)

set the placement for the desired joint control MC for a manipulator

DesiredVelocity
SGP <*, EcManipulatorEndEffectorVelocityVector> (EcManipulatorEndEffectorVelocityVector& value) get/set the desired MC velocities for all manipulators
SG <*, EcManipulatorEndEffectorVelocity> (const EcU32 manipIndex, EcManipulatorEndEffectorVelocity& value) get/set the desired MC velocities for a manipulator
SG <*, EcRealVector> (const EcU32 manipIndex, const EcU32 mcIndex, EcRealVector& mcVelocity)

get/set the desired MC velocity for a specific MC of a manipulator

DhFrame
G <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 linkIndex, EcCoordinateSystemTransformation&)

get the coordinates of DH frame for a specific link of a manipulator

DigitalInput
SG <*, EcU32Vector> (EcU32Vector& value) get/set the Digital Input vector. Used to communicate with an external device.
SG <*, EcU32> (const EcU32 inputIndex, EcU32& value)

get/set the Digital Input for a particular index

DigitalOutput
SG <*, EcU32Vector> (EcU32Vector& value) get/set the Digital Output vector. Used to communicate with an external device.
SG <*, EcU32> (const EcU32 boardIndex, EcU32& value) get/set the Digital Output for a particular board
S <*, EcBoolean> (const EcU32 boardId, const EcU32 channelId, const EcBoolean& value)

set the Digital Output for a specific channel of a specific board

DisplaySystemDataCapture
SG <*, EcDisplaySystemDataCaptureVector> (EcDisplaySystemDataCaptureVector& value)

get/set the EcDisplaySystemDataCapture for the system

DynamicSimulation
SGPr <*, EcDynamicSimulatorSystem> (EcDynamicSimulatorSystem& value) get/set the EcDynamicSimulatorSystem
SGP <*, EcBoolean> (EcBoolean& value) Turn on/off "Dynamic Simulation" capability for the system
SG <*, EcBoolean> (const EcU32 manipIndex, EcBoolean& value)

Turn on/off dynamic simulation capability for a manipulator in the system

EndEffector
S <*, EcU32> (const EcU32 manipIndex, EcU32& mcIndex)

get/set the Active motion constraint of a manipulator

EndEffectorSet
SGP <*, EcEndEffectorSetVector> (EcEndEffectorSetVector& value) get/set the active Motion Constraint Sets for the system
SG <*, EcEndEffectorSetVector> (const EcU32 manipIndex, EcEndEffectorSetVector& value) get/set the Motion Constraint Sets for a manipulator
SG <*, EcEndEffectorSet> (const EcU32 manipIndex, EcEndEffectorSet& value) get/set the active MCS for a manipulator
SG <*, EcEndEffectorSet> (const EcU32 manipIndex, const EcU32 mcSetIndex, EcEndEffectorSet& value) set method will replace the MCS at the mcSetIndex for a manipulator, except for JointControllerEndEffectorSet get method will return the MC Set at the specified mcSetIndex for a manipulator
SG <*, EcBoolean> (const EcU32 manipIndex, const EcBoolean& value) Turn on/off the use of Soft MCS for a manipulator
SG <*, EcU32> (const EcU32 manIndex, EcU32& activeMcSetIndex)

get/set the Active MCS of a manipulator to the specified activeMcSetIndex

ExternalControl
SP <*, EcBoolean> (EcBoolean& value) Turn on/off the ability to Externally control simulation components
S <*, EcManipulatorTorqueVector> (EcManipulatorTorqueVector& value) set the external torques to control manipulators during dynamic simulation
S <*, EcManipulatorTorque> (const EcU32 manipIndex, EcManipulatorTorque& value) set the external torque to control a specific manipulator during dynamic simulation
S <*, EcBooleanVectorVector> (EcBooleanVectorVector& value)

set which of the variable joint controllers would use the external control torque in the system

ForceControlDescriptor
SG <*, EcU32> (const EcU32 manIndex, EcU32& value)

get/set the active Force control descriptor to be used for a manipulator

ForceControlOn
SG <*, EcBoolean> (EcBoolean& value)

Turn on/off "Force Control"

HomeState
G <*, EcSystemSimulation> (EcSystemSimulation& value)

gets HomeState of the simulation

ImageSensor
G <*, EcImageSensor> (const EcU32 manipIndex, EcImageSensor& value) get the image sensor value for a specific manipulator
SG <*, EcImageSensorVector> (EcImageSensorVector& value)

get/set the image sensor values for the system

InitJointAngle
SG <*, EcRealVector> (const EcU32 manIndex, EcRealVector& value)

get/set the initial joint state for a manipulator

JointAngle
SG <*, EcRealVectorVector> (EcRealVectorVector& value) get/set the Joint positions for all the links of all the manipulators in the system
SG <*, EcRealVector> (const EcManipLinkIndexPairVector& manipLinkIndices, EcRealVector& value) get/set the Joint positions for specific links of specific manipulators specified by the manip-link vector
SG <*, EcRealVector> (const EcU32 manipIndex, EcRealVector& value) get/set the Joint positions for links of a manipulator
SG <*, EcReal> (const EcU32 manipIndex, const EcU32 jointIndex, EcReal& jointPos)

get/set the Joint position for a specific joint of a manipulator

JointController
SGPr <*, EcJointControllerSystemContainer> (EcJointControllerSystemContainer& value)

get/set the EcJointControllerSystemContainer for the system

JointVelocity
SG <*, EcRealVectorVector> (EcRealVectorVector& value) get/set the Joint velocity for all the joints of all manipulators in the system
SG <*, EcRealVector> (const EcU32 manipIndex, EcRealVector& value) get/set the Joint velocity for all the joints of a manipulator in the system
SG <*, EcReal> (const EcU32 manipIndex, const EcU32 jointIndex, EcReal& jointVel)

get/set the Joint velocity for a specific joint of a manipulator in the system

Manipulator
PrB <*, EcIndividualManipulatorVector> () get a const pointer to EcIndividualManipulatorVector for all manipulators in the system
S <*, EcIndividualManipulator> (const EcIndividualManipulator& value) add a new manipulator to the system
G <*, EcIndividualManipulator> (const EcU32 manipIndex, EcIndividualManipulator& value) get manipulator data of a manipulator in the system specified by manipIndex
G <*, EcIndividualManipulator> (const EcString& manipLabel, EcIndividualManipulator& value) get manipulator data of a manipulator in the system specified by manipulator name/label
G <*, EcManipulatorLink> (const EcU32 manipIndex, const EcU32 linkIndex, EcManipulatorLink& value) get manipulator link data of a specific link of a manipulator in the system
G <*, EcStringVector> (EcStringVector& manipLabels) get manipulator names/labels of all manipulators in the system
G <*, EcStringVector> (const EcU32 manipIndex, EcStringVector& linkLabels) get link names/labels of a manipulator in the system
SG<*, EcString> (const EcU32 manipIndex, EcString& manipLabel) get/set manipulator name/label of a manipulator in the system
G <*, EcString> (const EcU32 manipIndex, const EcU32 linkIndex, EcString& linkLabel) get link name/label of a specific link of a manipulator in the system
SG<*, EcU32> (EcU32& activeManipIndex) get/set active manipulator
S <*, EcU32> (const EcU32 manipIndex, const EcU32& cloneOrDelete) This method is used to clone or delete a manipulator identified by manipIndex. If cloneOrDelete is 0, specified manipulator is deleted else it is cloned
P <*, EcU32> ()

This method returns the number of manipulators in the system

ManipulatorSystemConfiguration
SG <*, EcManipulatorSystemConfiguration> (EcManipulatorSystemConfiguration& value)

get/set the attachment map and the collision exclusion map through the EcManipulatorSystemConfiguration

ManipulatorGraspingModule
SGPr <*, EcManipulatorGraspingModuleVector> (EcManipulatorGraspingModuleVector& value)

get/set the EcManipulatorGraspingModules for the system

ManipulatorLinkProps
S <*, EcManipulatorLink> (const EcU32 manipIndex, const EcU32 linkIndex, const EcManipulatorLink& value)

set the link data/properties for a specific link of a manipulator

MeasuredForce
SG <*, EcManipulatorSensorForce> (const EcU32 manipIndex, EcManipulatorSensorForce& val)

get/set the manipulator sensor force for a manipulator

MeasuredUpdatePeriod
P <*, EcReal> ()

returns the Time between calls to runSimulationCycle

NamedFrames
SG <*, EcNamedFrames> (const EcU32 manipIndex, const EcU32 linkIndex, EcNamedFrames& value) get/set the named frame for a specific link of a manipulator
SG <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 linkIndex, const EcString& key, EcCoordinateSystemTransformation& value) get/set the coordinates for an existing named frame identified by key at a specific link of a manipulator
SG <*, EcNamedFrames> (EcNamedFrames& value) get/set the named frame at the manipulator system level
SG <*, EcCoordinateSystemTransformation> (const EcString& key, EcCoordinateSystemTransformation& value)

get/set the coordinates for an existing named frame identified by key at the manipulator system level

NamedFramesInSystem
G <*, EcNamedFrames> (const EcU32 manipIndex, const EcU32 linkIndex, EcNamedFrames& value) get all the available named frames for a specific link of a manipulator in the system
G <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 linkIndex, const EcString& key, EcCoordinateSystemTransformation& value)

get the coordinates for a specific named frame identified by name/key at a specific link of a manipulator in the system

OutputWriterVector
SG <*, EcOutputWriterVector> (EcOutputWriterVector& value)

get/set the EcOutputWriterVector

PositionControlSystem
SGPr <*, EcPositionControlContainer> (EcPositionControlContainer& value) get/set the EcPositionControlContainer for the system
SGPr <*, EcPositionControlSystem> (EcPositionControlSystem& value)

get/set the EcPositionControlSystem for the system

PrimaryFrame
G <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 linkIndex, EcCoordinateSystemTransformation& value)

get/set the coordinates of primary frame for a specific link of a manipulator

ProfiledEndEffectors
S <*, EcU32Vector> (const EcU32 manipIndex, const EcU32Vector& value)

set the motion constraints specified as a vector of MC indices to use profiled position control for a manipulator

PropagationResults
G <*, EcPropagationResultDataVector> (EcPropagationResultDataVector& value) get the Propagation result data for the system
G <*, EcPropagationResultData> (const EcU32 manipIndex, EcPropagationResultData& value)

get the Propagation result data for a manipulator

Shape
S <*, EcShape> (const EcU32 manipIndex, const EcU32 linkIndex, EcShape& value)

Replace the shape of a link of a manipulator

SimulationHome
S <*, EcBoolean> (const EcBoolean& savePlacement)

Stores the current state as home state and If savePlacement is True, stores the desired placement also

SimRunState
SGP <*, SimulationRunState> (SimulationRunState& value)

get/set the simulation run state

SimulationMutex
G <*,EcSharedMutexLock> (EcSharedMutexLock& value) get the simulation mutex lock
G <*,EcSharedMutexSharedLock> (EcSharedMutexSharedLock& value)

get the simulation shared mutex lock

SimulationThreadUpdateRate
SP <*, EcReal> (const EcReal& value)

get/set the Simulation thread (IODataBroker) frame rate in Hz

SimulationReset
S <*,EcBoolean> (const EcBoolean& resetPlacement)

Reset the simulation to initial state. If resetPlacement is True, the desired EE placement is to be reset as well.

SimulationTime
G <*, EcTime> (EcTime& value)

get the current Simulation Time in seconds

SpeedFactor
SG <*, EcReal> (const EcU32 manipIndex, EcReal& value) get/set the Speed factor for a manipulator
S <*, EcReal> (const EcU32 manipIndex, const EcU32 mcSetIndex, const EcU32 mcIndex, EcReal& value)

get/set the Speed factor for a specific MC of a specific MCS of a manipulator

State
SGP <*, EcManipulatorSystemState> (EcManipulatorSystemState& value) get/set the manipulator system state as EcManipulatorSystemState
SG <*, EcPositionState> (const EcU32 manipIndex, EcPositionState& value) get/set the EcPositionState for a manipulator
SG <*, EcPositionState> (const EcU32 manipIndex, EcVelocityState& value)

get/set the EcVelocityState for a manipulator

StatedSystem
SPrB <*, EcStatedSystem> (EcStatedSystem& value)

get/set the EcStatedSystem

StaticCollisionExclusionMap
SG <*, EcSystemCollisionExclusionMap> (EcSystemCollisionExclusionMap& value)

get/set the static collision exclusion map for the system

StopMotion
S <*, EcBoolean> (const EcU32 manipIndex, const EcBoolean& stopOrResume) Stop or resume the motion of a manipulator. If stopOrResume is true, it causes a SoftStop else it is resume motion.
S <*, EcU32> (const EcU32 manipIndex, const EcU32& stopOrResume) Stop or resume the motion of joint motion consraint of a manipulator.
S <*, EcU32> (const EcU32 manipIndex, const EcU32 eeSetIndex, const EcU32& stopOrResume)

Stop or resume the motion of a specific motion consraint of a manipulator. stopOrResume in both the methods can take values from enumeration StopMode. If the value is other than ResumeMotion, the motion constraint will be stopped

SystemControlExecutive
Pr <*, EcSystemControlExecutive> ()

Retrieves a const pointer to the EcSystemControlExecutive

SystemDataCapture
SG <*, EcSystemDataCapture> (EcSystemDataCapture& value)

get/set the EcSystemDataCapture

SystemEnvironment
SG <*, EcSystemEnvironment> (EcSystemEnvironment& value)

get/set the EcSystemEnvironment

SystemSimulation
SGPrB <*, EcSystemSimulation> (EcSystemSimulation& value)

get/set the EcSystemSimulation

ToolOffset
G <*, EcSizeT> (const EcU32 manipIndex, EcSizeT& value) get the total number of ToolOffsets available for a manipulator
SG <*, EcCoordinateSystemTransformationVector> (const EcU32 manipIndex, EcCoordinateSystemTransformationVector& value) get/set the coordinates of all the ToolOffsets for a manipulator
SG <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 toolOffsetIndex, EcCoordinateSystemTransformation& value) get/set the coordinates of a specifc ToolOffset for a manipulator
SG <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 mcSetIndex, const EcU32 mcIndex, EcCoordinateSystemTransformation& value) get/set the coordinates of an external ToolOffset for a specific MC within a specific MCS of a manipulator
SG <*, EcCoordinateSystemTransformation> (const EcU32 manipIndex, const EcU32 mcSetIndex, const EcU32 mcIndex, const EcU32 toolOffsetIndex, EcCoordinateSystemTransformation& value)

get/set the ToolOffset index for a specific MC within a specific MCS of a manipulator

ToolOffsetFixEE
S <*, EcCoordinateSystemTransformation>(EcCoordinateSystemTransformation) (EcU32 manipIndex, EcU32 toolIndex, const EcCoordinateSystemTransformation)

set the Tool offset coordinates for a specific tool offset index of a manipulator (sets tool offset but does not move the MC)

ViewerParameters
SGP <*, EcViewerParameters> (EcViewerParameters& value)

get/set EcViewerParameters

VirtualActive
SP <*, EcBoolean> (const EcBoolean& value)

Check whether the virtual system is active

VirtualManipulatorIndex
G <*, EcU32> (const EcU32 manipIndex, EcU32& value)

Get the virtual manipulator index associated with the given manipulator index

WhatChanged
P <*, EcU32> (EcU32)

Changed bit flags

Detailed Parameter Descriptions

ActiveState

The Ec::ActiveState parameter provides access to the manipulator system active states (position, velocity, acceleration, force, mass, actuator parameters) through the EcManipulatorActiveStateVector, EcManipulatorActiveState, and EcSystemActiveState class objects.

Set/Get EcManipulatorActiveStateVector

The following methods can be used to set and get the EcManipulatorActiveStateVector object.

//------------------------------------------------------------------------------
// setParam<ActiveState, EcManipulatorActiveStateVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ActiveState, EcManipulatorActiveStateVector>
(
);
//------------------------------------------------------------------------------
// getParam<ActiveState, EcManipulatorActiveStateVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActiveState, EcManipulatorActiveStateVector>
(
) const;
//------------------------------------------------------------------------------
// param<ActiveState, EcManipulatorActiveStateVector>
//------------------------------------------------------------------------------
const EcManipulatorActiveStateVector Ec::Plugin::param<ActiveState, EcManipulatorActiveStateVector>
(
) const;

Set/Get EcManipulatorActiveState

The following methods can be used to set and get the EcManipulatorActiveState object based on manipulator index.

//------------------------------------------------------------------------------
// setParam<ActiveState, EcManipulatorActiveState>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ActiveState, EcManipulatorActiveStateVector>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<ActiveState, EcManipulatorActiveState>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActiveState, EcManipulatorActiveState>
(
const EcU32 manipulatorIndex,
) const;

Get EcSystemActiveState

The following method can be used to get the EcSystemActiveState object.

//------------------------------------------------------------------------------
// getParam<ActiveState, EcSystemActiveState>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActiveState, EcSystemActiveState>
(
) const;

ActualEndEffector

The Ec::ActualEndEffector parameter represents the actual location of end-effectors (Motion Constraints) in the system. For the desired placements see the DesiredEndEffector section.

Get the Actual Constraint Placements for all Manipulators

The following methods provide access to the actual EcManipulatorEndEffectorPlacementVector for the system of manipulators.

//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcManipulatorEndEffectorPlacementVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcManipulatorEndEffectorPlacementVector>
(
) const;
//------------------------------------------------------------------------------
// param<ActualEndEffector, EcManipulatorEndEffectorPlacementVector>
//------------------------------------------------------------------------------
Ec::Plugin::param<ActualEndEffector, EcManipulatorEndEffectorPlacementVector>
(
) const;

Get the Actual Constraint Placements for a Manipulator

The following methods provide access to the EcManipulatorEndEffectorPlacement object which holds a description of the placement of all end effectors (motion constraints) on a manipulator.

//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcManipulatorEndEffectorPlacement>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcManipulatorEndEffectorPlacement>
(
const EcU32 manipulatorIndex,
) const;
//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcManipulatorEndEffectorPlacement>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcManipulatorEndEffectorPlacement>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

Get an Actual Constraint Placement

As an EcEndEffectorPlacement

The following method provides access to an EcEndEffectorPlacement instance which describes an actual end-effector (motion constraint) placement as either a vector of real values or a coordinate system transformation.

//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcEndEffectorPlacement>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcEndEffectorPlacement>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

As a Coordinate System Transformation

The coordinate system transformation of an end-effector (motion constraint) placement in system coordinates can be obtained with the following method.

//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

Get Specific Parameters of an Actual Constraint Placement

Position and Orientation

The position and orientation can be obtained individually using the following methods.

//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcVector>
//------------------------------------------------------------------------------
Ec::Plugin::getParam<ActualEndEffector, EcVector>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcVector& value
) const;
//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcOrientation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcOrientation>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

General Velocity

This method is DEPRICATED. Use ActualVelocity instead The velocity at the actual end effector placement, as calculated through EcEndEffector::calculateVelocity can be retrieved using the following method.

//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcRealVector>
// Get the velocity vector for the end effector
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcRealVector>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcRealVector& value
) const;

Special Methods for Linear Constraints

For linear constraints, the Z value of the end effector placement represents the constraint value. These values can be obtained through the following methods.

//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcRealVector>
// Get vector of linear constraint Z-values from end-effector.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcRealVector>
(
const EcU32 manipulatorIndex,
EcRealVector& value
) const;
//------------------------------------------------------------------------------
// getParam<ActualEndEffector, EcReal>
// Convenience routine to get linear constraint Z-value from end-effector.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualEndEffector, EcReal>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcReal& value
) const;

ActualVelocity

The Ec::ActualVelocity parameter represents the actual velocity of end-effectors (Motion Constraints) in the system. For the desired velocity see the DesiredVelocity section.

//------------------------------------------------------------------------------
// getParam<ActualVelocity, EcManipulatorEndEffectorVelocity>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualVelocity, EcManipulatorEndEffectorVelocity>
(
const EcU32 manIndex,
) const;
//------------------------------------------------------------------------------
// getParam<ActualVelocity, EcRealVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ActualVelocity, EcRealVector>
(
const EcU32 manIndex,
const EcU32 subIndex,
EcRealVector& value
) const;

AntiCollision

The Ec::AntiCollision parameter provides the ability to set and get the on/off state of anti-collision used in manipulator system control using a EcBoolean flag.

//------------------------------------------------------------------------------
// getParam<AntiCollision, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<AntiCollision, EcBoolean>
(
const EcU32 manipulatorIndex,
EcBoolean& value
) const;
//------------------------------------------------------------------------------
// setParam<AntiCollision, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<AntiCollision, EcBoolean>
(
const EcU32 manipulatorIndex,
const EcBoolean& value
);

AttachmentMap

The Ec::AttachmentMap parameter provides access to the EcManipulatorAttachmentMap which describes attachments of one manipulator to another. For example, one can attach a hand manipulator onto an arm manipulator. An attachment consists of a dependent manipulator, a base manipulator, a link on the base manipulator to which the dependent manipulator is attached, and an offset, which is a transformation between the dependent manipulator's primary frame and the base link's primary frame.

//------------------------------------------------------------------------------
// setParam<AttachmentMap, EcManipulatorAttachmentMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<AttachmentMap, EcManipulatorAttachmentMap>
(
);
//------------------------------------------------------------------------------
// getParam<AttachmentMap, EcManipulatorAttachmentMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<AttachmentMap, EcManipulatorAttachmentMap>
(
) const;
//------------------------------------------------------------------------------
// setParam<AttachmentMap, EcManipulatorAttachmentChange>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<AttachmentMap, EcManipulatorAttachmentChange>
(
);

Base

The Ec::Base parameter provides access to the transformations defining the location each manipulator's base link in system coordinates.

Set/Get All Manipulator Base Transformations

The base link coordinate system transfromations for all manipulators can be set/get at once using the following methods.

//------------------------------------------------------------------------------
// setParam<Base, EcCoordinateSystemTransformationVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<Base, EcCoordinateSystemTransformationVector>
(
);
//------------------------------------------------------------------------------
// getParam<Base, EcCoordinateSystemTransformationVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<Base, EcCoordinateSystemTransformationVector>
(
) const;

Set/Get a Manipulator's Base Transformation

The base link coordinate system transfromation for a single manipulator can be set/get using the following methods.

//------------------------------------------------------------------------------
// setParam<Base, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<Base, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<Base, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<Base, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
) const;

Set/Get a Manipulator's Position and Orientation Independently

The position and orientation of a manipulator's base link can be set/get independently using the following methods.

//------------------------------------------------------------------------------
// setParam<Base, EcVector>
// Set the position of a manipulator's base link in system coordinates
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<Base, EcVector>
(
const EcU32 manipulatorIndex,
const EcVector& value
);
//------------------------------------------------------------------------------
// getParam<Base, EcVector>
// Get the position of a manipulator's base link in system coordinates
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<Base, EcVector>
(
const EcU32 manipulatorIndex,
EcVector& value
) const;
//------------------------------------------------------------------------------
// setParam<Base, EcOrientation>
// Set the orientation of a manipulator's base link in system coordinates
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<Base, EcOrientation>
(
const EcU32 manipulatorIndex,
const EcOrientation& value
);
//------------------------------------------------------------------------------
// getParam<Base, EcOrientation>
// Get the orientation of a manipulator's base link in system coordinates
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<Base, EcOrientation>
(
const EcU32 manipulatorIndex,
) const;

BaseVelocity

The Ec::BaseVelocity parameter is used to set and get the base velocity of a manipulator in system coordinates.

//------------------------------------------------------------------------------
// setParam<BaseVelocity, EcGeneralVelocity>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<BaseVelocity, EcGeneralVelocity>
(
const EcU32 manipulatorIndex,
const EcGeneralVelocity& value
);
//------------------------------------------------------------------------------
// getParam<BaseVelocity, EcGeneralVelocity>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<BaseVelocity, EcGeneralVelocity>
(
const EcU32 manipulatorIndex,
) const;

BaseSpeedFactor

The Ec::BaseSpeedFactor parameter is used to set the speed factor for all end-effector sets as well as the underlying controller. The value must be positive. Use value greater than 1 to speed up or value less than 1 to slow down the whole robot. See EcVelocityController::setBaseSpeedFactor.

//------------------------------------------------------------------------------
// getParam<BaseSpeedFactor, EcReal>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<BaseSpeedFactor, EcReal>
(
const EcU32 manipulatorIndex,
EcReal& value
) const;
//------------------------------------------------------------------------------
// setParam<BaseSpeedFactor, EcReal>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<BaseSpeedFactor, EcReal>
(
const EcU32 manipulatorIndex,
const EcReal& value
);

CalculationTime

The Ec::CalculationTime parameter is used to get the time (seconds) spent completing the last set of joint position calculations (see EcIODataBroker::runSimulationCycle).

//------------------------------------------------------------------------------
// param<CalculationTime, EcReal>
//------------------------------------------------------------------------------
const EcReal Ec::Plugin::param<CalculationTime, EcReal>
(
) const;

CollisionExclusionMap

The Ec::CollisionExclusionMap holds a map describing which collision pairs should be excluded from consideration. Collision pairs can be between two manipulators, between a manipulator and a specific link of another manipulator, or between two specific links of two different manipulators. This map is considered dynamic and can be changed at runtime. The static collision exclusion map should not change over time and is accessed with the StaticCollisionExclusionMap parameter.

Set/Get the System Collision Exclusion Map

The EcSystemCollisionExclusionMap defines which manipulators (and links) in a system will be checked for collision at each update cycle of the position controller. The following methods can be used to set and get the EcSystemCollisionExclusionMap object for the system.

//------------------------------------------------------------------------------
// setParam<CollisionExclusionMap, EcSystemCollisionExclusionMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<CollisionExclusionMap, EcSystemCollisionExclusionMap>
(
);
//------------------------------------------------------------------------------
// getParam<CollisionExclusionMap, EcSystemCollisionExclusionMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<CollisionExclusionMap, EcSystemCollisionExclusionMap>
(
) const;

Set/Get the Self Collision Map for a Manipulator

The EcManipulatorSelfCollisionLinkMap object, which defines which links on a manipulator will be checked for self collision, can be set/get for a given manipulator using the following methods.

//------------------------------------------------------------------------------
// setParam<CollisionExclusionMap, EcManipulatorSelfCollisionLinkMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<CollisionExclusionMap, EcManipulatorSelfCollisionLinkMap>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<CollisionExclusionMap, EcManipulatorSelfCollisionLinkMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<CollisionExclusionMap, EcManipulatorSelfCollisionLinkMap>
(
const EcU32 manipulatorIndex,
) const;

CollisionPriority

The Ec::CollisionPriority parameter sets or gets the priority list defined by EcAntiCollisionPriorityList used by the anti-collision position controller EcAntiCollisionPositionController.

Note
Setting the collision priority list parameter will only take effect if an EcAntiCollisionPositionController is used in the system. If no EcAntiCollisionPositionController is present then methods will return true, but will not have any effect.
//------------------------------------------------------------------------------
// setParam<CollisionPriority, EcAntiCollisionPriorityList>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<CollisionPriority, EcAntiCollisionPriorityList>
(
);
//------------------------------------------------------------------------------
// getParam<CollisionPriority, EcAntiCollisionPriorityList>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<CollisionPriority, EcAntiCollisionPriorityList>
(
) const;

CollisionStop

The Ec::CollisionStop parameter can be used to turn on/off stops at collision in the control system for a given manipulator. If set to true, then the manipulator will stop when a collision is detected, otherwise it will continue moving. The method below calls EcPositionControlSystem::setCollisionStop.

//------------------------------------------------------------------------------
// setParam<CollisionStop, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<CollisionStop, EcBoolean>
(
const EcU32 manipulatorIndex,
const EcBoolean& value
);

ControlDescriptor

The Ec::ControlDescriptor parameter can be used to set or get the index of the current control system descriptor for a single manipulator. This is used to switch the control descriptor if the manipulator has more than one. See EcPositionControlSystem::activeControlDescriptionIndex and EcPositionControlSystem::setActiveControlDescription for details.

//------------------------------------------------------------------------------
// setParam<ControlDescriptor, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ControlDescriptor, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32& value
);
//------------------------------------------------------------------------------
// getParam<ControlDescriptor, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ControlDescriptor, EcU32>
(
const EcU32 manipulatorIndex,
EcU32& value
) const;

Get Control Descriptor Labels for a Manipulator's Controller

The following method gets a vector of string labels (labels) of the Control Descriptors (EcControlExpressionDescription) for a given manipulator index (manipulatorIndex). See EcControlExpressionDescription::label.

//------------------------------------------------------------------------------
// getParam<ControlDescriptor, EcStringVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ControlDescriptor, EcStringVector>
(
const EcU32 manipulatorIndex,
) const

ControlMethod

Set/Get Control Method for a Manipulator

The Ec::ControlMethod parameter is used to get and set the index of the active position control method in the position controller. Each manipulator has an associated EcPositionController which has a EcPositionControlMethodVector. The methods below are used to set the active control method element in this vector. See EcPositionControlSystem::activeControlMethod and EcPositionControlSystem::setActiveControlMethod.

//------------------------------------------------------------------------------
// setParam<ControlMethod, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ControlMethod, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32& value
);
//------------------------------------------------------------------------------
// getParam<ControlMethod, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ControlMethod, EcU32>
(
const EcU32 manipulatorIndex,
EcU32& value
) const;

Get Control Method Labels for a Manipulator's Controller

The following method gets a vector of string XML tokens (tokens) of the Control Method for a given manipulator index (manipulatorIndex). See EcPositionController::positionControlMethods.

//------------------------------------------------------------------------------
// getParam<ControlMethod, EcStringVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ControlMethod, EcStringVector>
(
const EcU32 manipulatorIndex,
) const

ControlMode

The Ec::ControlMode parameter is used to set and get the active control mode for a manipulator's position controller. The available modes are defined in an enum encapsulated by the EcPositionController class. The control mode values and accessor methods are defined in the table and code block below.

Control Mode Description
EcEndEffector::POSITION_CONTROL Position control mode
EcEndEffector::VELOCITY_CONTROL Velocity control mode
EcEndEffector::PROFILED_POSITION Position control mode to be used when streaming positions frequently as in the case of path following.
//------------------------------------------------------------------------------
// setParam<ControlMode, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ControlMode, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32& value
);
//------------------------------------------------------------------------------
// getParam<ControlMode, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ControlMode, EcU32>
(
const EcU32 manipulatorIndex,
EcU32& value
) const;

ControlSystem

The Ec::ControlSystem sets the force and position control system held by the system simulation (EcSystemSimulation) object.

1 ### Set/Get the Position Control System and Container
2 
3 The EcPositionControlContainer can be set/get with following methods.
4 
5 ~~~~~~~~~~~~~~~{.cpp}
6 
7  //------------------------------------------------------------------------------
8  // setParam<ControlSystem, EcPositionControlContainer>
9  //------------------------------------------------------------------------------
10  EcBoolean Ec::Plugin::setParam<ControlSystem, EcPositionControlContainer>
11  (
12  const EcPositionControlContainer& value
13  );
14 
15  //------------------------------------------------------------------------------
16  // getParam<ControlSystem, EcPositionControlContainer>
17  //------------------------------------------------------------------------------
18  EcBoolean Ec::Plugin::getParam<ControlSystem, EcPositionControlContainer>
19  (
20  EcPositionControlContainer& value
21  ) const;
22 
23  //------------------------------------------------------------------------------
24  // paramPtr<ControlSystem, EcPositionControlContainer>
25  // Callers should acquire the SimulationMutex lock beforehand if using the paramPtr accessor.
26  //------------------------------------------------------------------------------
27  const EcPositionControlContainer* Ec::Plugin::paramPtr<ControlSystem, EcPositionControlContainer>
28  (
29  ) const;

The EcPositionControlSystem can be set/get with the following methods.

//------------------------------------------------------------------------------
// setParam<ControlSystem, EcPositionControlSystem>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ControlSystem, EcPositionControlSystem>
(
);
//------------------------------------------------------------------------------
// getParam<ControlSystem, EcPositionControlSystem>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ControlSystem, EcPositionControlSystem>
(
) const;
//------------------------------------------------------------------------------
// paramPtr<ControlSystem, EcPositionControlSystem>
// Callers should acquire the SimulationMutex lock beforehand if using the paramPtr accessor.
//------------------------------------------------------------------------------
Ec::Plugin::paramPtr<ControlSystem, EcPositionControlSystem>
(
) const;

Set/Get the Position Control System On/Off State

The position control system on/off state can be set/get using the following methods. Setting the on/off state to false will disable the position control system. This is useful if the system state is being set explictly by another plugin. The ExternalControl parameter can be used to accomplish this as well.

//------------------------------------------------------------------------------
// setParam<ControlSystem, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ControlSystem, EcBoolean>
(
const EcBoolean& value
);
//------------------------------------------------------------------------------
// getParam<ControlSystem, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ControlSystem, EcBoolean>
(
EcBoolean& value
) const;
//------------------------------------------------------------------------------
// param<ControlSystem, EcBoolean>
//------------------------------------------------------------------------------
const EcBoolean Ec::Plugin::param<ControlSystem, EcBoolean>
(
) const;

Set/Get the On/Off State of a Manipulator's Position Controller

A manipulator's position controller on/off state can be set/get using the following methods. Setting the on/off state to false will disable the position controller for the manipulator idetified by manipulatorIndex.

//------------------------------------------------------------------------------
// setParam<ControlSystem, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ControlSystem, EcBoolean>
(
const EcU32 manipulatorIndex,
const EcBoolean& value
);
//------------------------------------------------------------------------------
// getParam<ControlSystem, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ControlSystem, EcBoolean>
(
const EcU32 manipulatorIndex,
EcBoolean& value
) const;

DataMap

The Ec::DataMap parameter can be used to set/get the EcDataMap object used to organize general data that can be shared among plugins. Data stored in this map only persists for the lifetime of the application and is not saved with the simulation file. See Ec::IOBuffer::m_DataMap.

//------------------------------------------------------------------------------
// setParam<DataMap, EcDataMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DataMap, EcDataMap>
(
const EcDataMap& value
);
//------------------------------------------------------------------------------
// getParam<DataMap, EcDataMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DataMap, EcDataMap>
(
EcDataMap& value
) const;

DesiredEndEffector

The Ec::DesiredEndEffector parameter provides access the desired end-effector (Motion Constraints) placements. During a simulation time step, the control system calculates movement to take the manipulators from the actual location to the desired location. For the actual placements see the ActualEndEffector section.

Set/Get Desired Constraint Placements for all Manipulators

The following methods can be used to set and get the desired EcManipulatorEndEffectorPlacementVector for the system of manipulators.

//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcManipulatorEndEffectorPlacementVector>
// Sets the complete set of desired end-effector poses for all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, EcManipulatorEndEffectorPlacementVector>
(
);
//------------------------------------------------------------------------------
// getParam<DesiredEndEffector, EcManipulatorEndEffectorPlacementVector>
// Gets the complete set of desired end-effector poses for all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredEndEffector, EcManipulatorEndEffectorPlacementVector>
(
) const;
//------------------------------------------------------------------------------
// param<DesiredEndEffector, EcManipulatorEndEffectorPlacementVector>
// Returns the complete set of desired end-effector poses for all manipulators.
//------------------------------------------------------------------------------
Ec::Plugin::param<DesiredEndEffector, EcManipulatorEndEffectorPlacementVector>
(
) const;

Set/Get Desired Constraint Placements for a Manipulator

The following methods are used to set and get the EcManipulatorEndEffectorPlacement object for a single manipulator.

//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcManipulatorEndEffectorPlacement>
// Sets the EcManipulatorEndEffectorPlacement for a single manipulator
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, EcManipulatorEndEffectorPlacement>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<DesiredEndEffector, EcManipulatorEndEffectorPlacement>
// Gets the EcManipulatorEndEffectorPlacement for a single manipulator
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredEndEffector, EcManipulatorEndEffectorPlacement>
(
const EcU32 manipulatorIndex,
) const;

Get/Set a Desired Constraint Placement

As an EcEndEffectorPlacement

//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcEndEffectorPlacement>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, EcEndEffectorPlacement>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
);
//------------------------------------------------------------------------------
// getParam<DesiredEndEffector, EcEndEffectorPlacement>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredEndEffector, EcEndEffectorPlacement>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

As a Coordinate System Transfromation

The desired end-effector placement can be set/get through an EcCoordinateSystemTransformation with the following methods.

//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
);
//------------------------------------------------------------------------------
// getParam<DesiredEndEffector, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredEndEffector, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

Get Specific Parameters of a Desired Constraint Placement

Position and Orientation

The position and orientation can be obtained individually using the following methods.

//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, EcVector>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
const EcVector& value
);
//------------------------------------------------------------------------------
// getParam<DesiredEndEffector, EcVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredEndEffector, EcVector>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcVector& value
) const;
//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcOrientation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, EcOrientation>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
const EcOrientation& value
);
//------------------------------------------------------------------------------
// getParam<DesiredEndEffector, EcOrientation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredEndEffector, EcOrientation>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

Special Methods for Linear Constraints

For linear constraints, the Z value of the desired end-effector placement represents the constraint value. These values can be obtained through the following methods.

//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcRealVector>
// Specialization for DesiredEndEffector to handle linear constraint EEs.
// It will take the incoming value and populate the Z components.
// Populates manipulator index
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, EcRealVector>
(
const EcU32 manipulatorIndex,
const EcRealVector& value
);
//------------------------------------------------------------------------------
// getParam<DesiredEndEffector, EcRealVector>
// Convenience routine to get vector of linear constraint Z-values from end-effector.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredEndEffector, EcRealVector>
(
const EcU32 manipulatorIndex,
EcRealVector& value
) const;
//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcReal>
// Specialization for DesiredEndEffector to handle linear constraint EEs.
// It will take the incoming value and populate the Z component.
// Populates manipulator index as well as EE/link index
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, EcReal>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
const EcReal& value
);
//------------------------------------------------------------------------------
// getParam<DesiredEndEffector, EcReal>
// Convenience routine to get linear constraint Z-value from end-effector.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredEndEffector, EcReal>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcReal& value
) const;

Set All Desired Placements to Actual

The following method can be used to set all desired end-effector (motion constraint) placements to the current actual placements. In this method, the value argument is provided but unused.

//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, ParamTypeEnum>
// Convenience routine to set desired EE to actual in one call.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredEndEffector, ParamTypeEnum>
(
const ParamTypeEnum& value
)
{
IMPL_CHECK;
return setParam<DesiredEndEffector>( param<ActualEndEffector, EcManipulatorEndEffectorPlacementVector>() );
}

DesiredForce

The Ec::DesiredForce parameter can be used to get and set the desired force values on manipulators in the system.

Set/Get Force Sensor Data for all Manipulators

Sets and gets a description of the desired forces of all sensors on all manipulators in a system through the EcManipulatorSensorForceVector object.

//------------------------------------------------------------------------------
// setParam<DesiredForce, EcManipulatorSensorForceVector>
// Sets a description of the desired forces of all sensors on all the manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredForce, EcManipulatorSensorForceVector>
(
);
//------------------------------------------------------------------------------
// getParam<DesiredForce, EcManipulatorSensorForceVector>
// Gets a description of the desired forces of all sensors on all the manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredForce, EcManipulatorSensorForceVector>
(
) const;
//------------------------------------------------------------------------------
// param<DesiredForce, EcManipulatorSensorForceVector>
// Returns a description of the desired forces of all sensors on all the manipulators.
//------------------------------------------------------------------------------
const EcManipulatorSensorForceVector Ec::Plugin::param<DesiredForce, EcManipulatorSensorForceVector>
(
) const;

Set/Get Force Sensor Data for a Manipulator

Sets and gets a description of the desired forces of all sensors on a single manipulator through the EcManipulatorSensorForce object.

//------------------------------------------------------------------------------
// setParam<DesiredForce, EcManipulatorSensorForce>
// Sets a description of the desired forces of all sensors for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredForce, EcManipulatorSensorForce>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<DesiredForce, EcManipulatorSensorForce>
// Gets a description of the desired forces of all sensors for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredForce, EcManipulatorSensorForce>
(
const EcU32 manipulatorIndex,
) const;

DesiredJointControlEndEffector

This parameter is used to set the desired placement for linear motion constraints. It will take the incoming value and utilize the Z component to set the linear constraint.

//------------------------------------------------------------------------------
// setParam<DesiredEndEffector, EcReal>
// Specialization for DesiredEndEffector to handle linear constraint EEs.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredJointControlEndEffector, EcEndEffectorPlacement>
(
const EcU32 manipulatorIndex,
);

DesiredVelocity

The desired velocity is the rate with which to move the end-effectors while moving from the actual location to the desired location. This is only applicable if the control mode in the control system is set to velocity control (see ControlMode for the methods to set the velocity control mode).

Get/Set Desired End-Effector Velocities on all Manipulators

The following methods can be used to set and get the desired velocites for all end-effectors (motion constraints) on all manipulators at once. See Ec::IOBuffer::setDesiredVelocityVector.

//------------------------------------------------------------------------------
// setParam<DesiredVelocity, EcManipulatorEndEffectorVelocityVector>
// Set the complete set of desired end-effector velocities for all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredVelocity, EcManipulatorEndEffectorVelocityVector>
(
);
//------------------------------------------------------------------------------
// getParam<DesiredVelocity, EcManipulatorEndEffectorVelocityVector>
// Get the complete set of desired end-effector velocities for all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredVelocity, EcManipulatorEndEffectorVelocityVector>
(
) const;
//------------------------------------------------------------------------------
// param<DesiredVelocity, EcManipulatorEndEffectorVelocityVector>
// Return the complete set of desired end-effector velocities for all manipulators.
//------------------------------------------------------------------------------
const EcManipulatorEndEffectorVelocityVector Ec::Plugin::param<DesiredVelocity, EcManipulatorEndEffectorVelocityVector>
(
) const;

Get/Set Desired End-Effector Velocities on a Manipulator

See Ec::IOBuffer::setDesiredVelocity.

//------------------------------------------------------------------------------
// setParam<DesiredVelocity, EcManipulatorEndEffectorVelocity>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredVelocity, EcManipulatorEndEffectorVelocity>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<DesiredVelocity, EcManipulatorEndEffectorVelocity>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredVelocity, EcManipulatorEndEffectorVelocity>
(
const EcU32 manipulatorIndex,
) const;

Alternatively, the velocities can be set using an EcRealVector through the following methods. See Ec::IOBuffer::setDesiredVelocity.

//------------------------------------------------------------------------------
// setParam<DesiredVelocity, EcRealVector>
// Set the set of desired end-effector velocities for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DesiredVelocity, EcRealVector>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
const EcRealVector& value
);
//------------------------------------------------------------------------------
// getParam<DesiredVelocity, EcRealVector>
// Get the set of desired end-effector velocities for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DesiredVelocity, EcRealVector>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcRealVector& value
) const;

DhFrame

The Ec::DhFrame parameter can be used to get the Denavit Hartenberg (DH) frame of the manipulator's links in system coordinates. Every link on every manipulator in the system has a rigidly attached 3D coordinate system transformation (frame) called the DH Frame. If you know the position and orientation of the DH Frame, you can determine the position and orientation of the link. The DH Frame is rigidly connected to the Primary Frame (see PrimaryFrame).

//------------------------------------------------------------------------------
// getParam<DhFrame, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DhFrame, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

DigitalInput

Set/Get a Vector of Digital Input Values

The vector of digital input values can be set or get using the following methods.

//------------------------------------------------------------------------------
// setParam<DigitalInput, EcU32Vector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DigitalInput, EcU32Vector>
(
const EcU32Vector& value
);
//------------------------------------------------------------------------------
// getParam<DigitalInput, EcU32Vector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DigitalInput, EcU32Vector>
(
EcU32Vector& value
) const;

Set/Get a single Digital Input Value

A single digital input value can be set or get using the following methods. The input parameter is the digital channel index.

//------------------------------------------------------------------------------
// setParam<DigitalInput, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DigitalInput, EcU32>
(
const EcU32 index,
const EcU32& value
)
//------------------------------------------------------------------------------
// getParam<DigitalInput, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DigitalInput, EcU32>
(
const EcU32 index,
EcU32& value
) const;

DigitalOutput

Set/Get a Vector of Digital Output Values

The vector of digital output values can be set or get using the following methods.

//------------------------------------------------------------------------------
// setParam<DigitalOutput, EcU32Vector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DigitalOutput, EcU32Vector>
(
const EcU32Vector& value
);
//------------------------------------------------------------------------------
// getParam<DigitalOutput, EcU32Vector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DigitalOutput, EcU32Vector>
(
EcU32Vector& value
) const;

Set/Get a single Digital Output Value

A single digital output value can be set or get using the following methods. The input parameter is the digital channel index.

//------------------------------------------------------------------------------
// setParam<DigitalOutput, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DigitalOutput, EcU32>
(
const EcU32 index,
const EcU32& value
)
//------------------------------------------------------------------------------
// getParam<DigitalOutput, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DigitalOutput, EcU32>
(
const EcU32 index,
EcU32& value
) const;

DisplaySystemDataCapture

The Ec::DisplaySystemDataCapture parameter is used to configure multiple data capture objects for display (plotting). The xml vector of EcDisplaySystemDataCapture objects is used to set and get data capture configurations through the following methods. The data display feature in ActinViewer is described on the Data Plot Plugin page.

//------------------------------------------------------------------------------
// setParam<DisplaySystemDataCapture, EcDisplaySystemDataCaptureVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DisplaySystemDataCapture, EcDisplaySystemDataCaptureVector>
(
);
//------------------------------------------------------------------------------
// getParam<DisplaySystemDataCapture, EcDisplaySystemDataCaptureVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DisplaySystemDataCapture, EcDisplaySystemDataCaptureVector>
(
) const;

DynamicSimulation

The Ec::DynamicSimulation parameter is used to set or get the dynamic simulator system for all manipulators. This parameter is also used to set/get the on/off state the dynamic simulators at the system and maniuplator level.

Set/Get EcDynamicSimulatorSystem

The following methods can be used to set or get the entire EcDynamicSimulatorSystem object.

//------------------------------------------------------------------------------
// setParam<DynamicSimulation, EcDynamicSimulatorSystem>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DynamicSimulation, EcDynamicSimulatorSystem>
(
);
//------------------------------------------------------------------------------
// getParam<DynamicSimulation, EcDynamicSimulatorSystem>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DynamicSimulation, EcDynamicSimulatorSystem>
(
) const;
//------------------------------------------------------------------------------
// paramPtr<DynamicSimulation, EcDynamicSimulatorSystem>
//------------------------------------------------------------------------------
Ec::Plugin::paramPtr<DynamicSimulation, EcDynamicSimulatorSystem>
(
) const;

Set/Get the Dynamic Simulation System On/Off State

The following methods can be used to set or get the dynamic simualation system's on/off state. See EcSystemSimulation::dynamicallySimulate.

//------------------------------------------------------------------------------
// setParam<DynamicSimulation, EcBoolean>
// This version is used to set the on/off state of the entire dynamic simulation system.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DynamicSimulation, EcBoolean>
(
const EcBoolean& value
);
//------------------------------------------------------------------------------
// getParam<DynamicSimulation, EcBoolean>
// This version is used to get the on/off state of the entire dynamic simulation system.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DynamicSimulation, EcBoolean>
(
EcBoolean& value
) const;
//------------------------------------------------------------------------------
// param<DynamicSimulation, EcBoolean>
// This version is used to return the on/off state of the entire dynamic simulation system.
//------------------------------------------------------------------------------
const EcBoolean Ec::Plugin::param<DynamicSimulation, EcBoolean>
(
) const;

Set/Get the Individual Dynamic Simulator On/Off State

The following methods can be used to set or get the on/off state of an individual manipulator's dynamic simualator. See EcDynamicSimulatorSystem::setManipulatorDynamicallySimulate.

//------------------------------------------------------------------------------
// getParam<DynamicSimulation, EcBoolean>
// This version is used to get the on/off state of the selected manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<DynamicSimulation, EcBoolean>
(
const EcU32 manipulatorIndex,
EcBoolean& value
) const;
//------------------------------------------------------------------------------
// setParam<DynamicSimulation, EcBoolean>
// This version is used to set the on/off state of the selected manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<DynamicSimulation, EcBoolean>
(
const EcU32 manipulatorIndex,
const EcBoolean& value
);

EndEffector

The Ec::EndEffector parameter can be used to get and set the active end-effector (motion constraint) index in the active end-effector set for a given manipulator. The active end-effector set can be selected using EndEffectorSet parameter. For more on the active end-effector index see EcPositionControlSystem::activeEndEffectorIndex and EcPositionControlSystem::setActiveEndEffectorIndex.

//------------------------------------------------------------------------------
// setParam<EndEffector, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<EndEffector, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32& value
);
//------------------------------------------------------------------------------
// getParam<EndEffector, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<EndEffector, EcU32>
(
const EcU32 manipulatorIndex,
EcU32& value
) const;

EndEffectorSet

End effector sets (EcEndEffectorSet) are collections of the end effectors (motion constraints) applied to a manipulator. The end effectors form the constraints on the system and meeting these constraints is the means by which manipulators and joints are moved during the simulation.

Set the UseSoftEndEffectorSet flag

//------------------------------------------------------------------------------
// setParam<EndEffectorSet, EcBoolean>
// Sets the flag to use a soft end-effector set if available.
// Calls Ec::IOBuffer::setUseSoftEndEffectorSet
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<EndEffectorSet, EcBoolean>
(
const EcU32 manipulatorIndex,
const EcBoolean& value
);

Set/Get all End Effector Sets for a Manipulator

The following methods can be used to set and get the vector of EcEndEffectorSet objects for a single manipulator.

//------------------------------------------------------------------------------
// setParam<EndEffectorSet, EcEndEffectorSetVector>
// Sets the EndEffectorSets for a given manipulator
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<EndEffectorSet, EcEndEffectorSetVector>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<EndEffectorSet, EcEndEffectorSetVector>
// Gets the EndEffectorSets for a given manipulator
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<EndEffectorSet, EcEndEffectorSetVector>
(
const EcU32 manipulatorIndex,
) const;

Set/Get an End Effector Set of a Manipulator

The following methods can be used to set and get an EcEndEffectorSet of a single manipulator.

//------------------------------------------------------------------------------
// setParam<EndEffectorSet, EcEndEffectorSet>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<EndEffectorSet, EcEndEffectorSet>
(
const EcU32 manipulatorIndex,
const EcU32 endEffectorSetIndex,
const EcEndEffectorSet& value
);
//------------------------------------------------------------------------------
// getParam<EndEffectorSet, EcEndEffectorSet>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<EndEffectorSet, EcEndEffectorSet>
(
const EcU32 manipulatorIndex,
const EcU32 endEffectorSetIndex,
) const;

Set/Get the Active End Effector Sets for all Manipulators

The following methods can be used to set and get all active EcEndEffectorSet objects for all manipulators at once.

//------------------------------------------------------------------------------
// setParam<EndEffectorSet, EcEndEffectorSetVector>
// Sets the active set of end-effectors used for all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<EndEffectorSet, EcEndEffectorSetVector>
(
);
//------------------------------------------------------------------------------
// getParam<EndEffectorSet, EcEndEffectorSetVector>
// Gets the active set of end-effectors used for all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<EndEffectorSet, EcEndEffectorSetVector>
(
) const;
//------------------------------------------------------------------------------
// param<EndEffectorSet, EcEndEffectorSetVector>
// returns the set of end-effectors used for all manipulators.
//------------------------------------------------------------------------------
Ec::Plugin::param<EndEffectorSet, EcEndEffectorSetVector>
(
) const;

Set/Get the End Effector Set for a Manipulator

The following methods can be used to get the EcEndEffectorSet object for a single manipulator.

//------------------------------------------------------------------------------
// setParam<EndEffectorSet, EcEndEffectorSet>
// Sets the set of end-effectors used for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<EndEffectorSet, EcEndEffectorSet>
(
const EcU32 manipulatorIndex,
const EcEndEffectorSet& value
);
//------------------------------------------------------------------------------
// getParam<EndEffectorSet, EcEndEffectorSet>
// Gets the set of end-effectors used for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<EndEffectorSet, EcEndEffectorSet>
(
const EcU32 manipulatorIndex,
) const;

Set/Get the Active End Effector Set for a Manipulator

The following methods can be used to get or set the active end-effector set based on index for a manipulator. The index defines the active element in the EcEndEffectorSetVector for a manipulator's position controller (See EcPositionController::setActiveEndEffectorSet). To select the active end effector (motion constraint) in the active set use the EndEffector parameter.

//------------------------------------------------------------------------------
// setParam<EndEffectorSet, EcU32>
// Sets the active end-effector set index for the selected manipulator
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<EndEffectorSet, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32& value
);
//------------------------------------------------------------------------------
// getParam<EndEffectorSet, EcU32>
// Gets the active end-effector set index for the selected manipulator
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<EndEffectorSet, EcU32>
(
const EcU32 manipulatorIndex,
EcU32& value
) const;

ExternalControl

The Ec::ExternalControl parameter can be used to set/get the on/off state of the position control system (EcPositionControlSystem), and it can be used to set or get external control torques used in dynamic simulation.

Set/Get the Position Control System On/Off State

This is done by setting the On/Off state for the Position Control system. For example, if the joint states all the manipulators in the system are being read from hardware, then setting Ec::ExternalControl to true would allow the hardware states to be set without calculating joint states through the position control system. The ControlSystem parameter can be used to accomplish this as well. See JointAngle and State for methods to set the manipulator states explicitly.

//------------------------------------------------------------------------------
// setParam<ExternalControl, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ExternalControl, EcBoolean>
(
const EcBoolean& value
);
//------------------------------------------------------------------------------
// param<ExternalControl, EcBoolean>
//------------------------------------------------------------------------------
const EcBoolean Ec::Plugin::param<ExternalControl, EcBoolean>
(
) const;

Set/Get External Torques

The following methods can be used to set or get external torques to be used in dynamic simulation. One example of where this might be used is in the dynamic simulation of a mobile wheeled vehicle, where torques can be applied to the wheels to simulate an engine and drivetrain. See EcSystemSimulation::setExternalControlTorques and EcSystemSimulation::setExternalControlTorque.

//------------------------------------------------------------------------------
// setParam<ExternalControl, EcManipulatorTorqueVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ExternalControl, EcManipulatorTorqueVector>
(
);
//------------------------------------------------------------------------------
// setParam<ExternalControl, EcManipulatorTorque>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ExternalControl, EcManipulatorTorque>
(
const EcU32 manipulatorIndex,
const EcManipulatorTorque& value
);

The following methods can be used to set which control torques/inputs are specified and should NOT be computed in EcBaseJointControllerSystem::calculateControlTorques or EcBaseJointControllerSystem::calculateControlInputs methods. See EcBaseJointControllerSystem::setSpecifyControlTorqueFlags.

//------------------------------------------------------------------------------
// setParam<ExternalControl, EcBooleanVectorVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ExternalControl, EcBooleanVectorVector>
(
const EcBooleanVectorVector& value
);

ForceControlDescriptor

The Ec::ForceControlDescriptor parameter is used to set and get the index of the active Force Control Description (EcForceControlDescription) in the vector EcForceControlSystem::m_ControlDescriptionVectors. See EcSystemSimulation::setActiveForceControlDescription.

//------------------------------------------------------------------------------
// setParam<ForceControlDescriptor, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ForceControlDescriptor, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32& value
);
//------------------------------------------------------------------------------
// getParam<ForceControlDescriptor, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ForceControlDescriptor, EcU32>
(
const EcU32 manipulatorIndex,
EcU32& value
) const;

ForceControlOn

The Ec::ForceControlOn parameter can be used to set or get the on/off state of the force control system in the simulation. The state is true if force control is on.

//------------------------------------------------------------------------------
// setParam<ForceControlOn, EcBoolean>
// Turns force control on or off
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ForceControlOn, EcBoolean>
(
const EcBoolean& value
);
//------------------------------------------------------------------------------
// getParam<ForceControlOn, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ForceControlOn, EcBoolean>
(
EcBoolean& value
) const;

HomeState

The Ec::HomeState parameter can be used to apply or get the Home state of the system. The following methods provide an interface to the Ec::IOBuffer::setHomePosition and Ec::IOBuffer::getHomePosition methods. The value arguement in the setParam method is not used and can be set to either true or false.

//------------------------------------------------------------------------------
// setParam<HomeState>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<SimulationHome, EcBoolean>
(
const EcBoolean& value
);
//------------------------------------------------------------------------------
// getParam<HomeState, EcSystemSimulation>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<HomeState, EcSystemSimulation>
(
) const;

ImageSensor

The Ec::ImageSensor parameter can be used to get or set image sensors, which derive from EcImageSensor, in the scene.

//------------------------------------------------------------------------------
// setParam<ImageSensor, EcImageSensorVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ImageSensor, EcImageSensorVector>
(
const EcImageSensorVector& value
);
//------------------------------------------------------------------------------
// getParam<ImageSensor, EcImageSensorVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ImageSensor, EcImageSensorVector>
(
) const;
//------------------------------------------------------------------------------
// getParam<ImageSensor, EcImageSensor>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ImageSensor, EcImageSensor>
(
const EcU32 manipulatorIndex,
) const;

InitJointAngle

The initial joint angle information is used when the simulation is stopped. It is the state at which the simulation is in when a file is loaded. This is used with real hardware on startup to set the simulation to the actual state of the hardware.

//------------------------------------------------------------------------------
// setParam<InitJointAngle, EcRealVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<InitJointAngle, EcRealVector>
(
const EcU32 manipulatorIndex,
const EcRealVector& value
);
//------------------------------------------------------------------------------
// getParam<InitJointAngle, EcRealVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<InitJointAngle, EcRealVector>
(
const EcU32 manipulatorIndex,
EcRealVector& value
) const;

JointAngle

The Ec::JointAngle parameter can be used to specify or retrieve the joint angles for manipulators.

Set/Get all Joint Positions for all Manipulators

The following methods can be used to set or get all joint angles for all manipulators in an EcRealVectorVector.

//------------------------------------------------------------------------------
// setParam<JointAngle, EcRealVectorVector>
// Set current joint angles for all joints in all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<JointAngle, EcRealVectorVector>
(
const EcRealVectorVector& value
);
//------------------------------------------------------------------------------
// getParam<JointAngle, EcRealVectorVector>
// Get current joint angles for all joints in all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<JointAngle, EcRealVectorVector>
(
) const;

Set/Get all Joint Positions for a Manipulator

The following methods can be used to set or get the positions of all joints on a single manipulator.

//------------------------------------------------------------------------------
// setParam<JointAngle, EcRealVector>
// Set joint angles for all joints in a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<JointAngle, EcRealVector>
(
const EcU32 manipulatorIndex,
const EcRealVector& value
);
//------------------------------------------------------------------------------
// getParam<JointAngle, EcRealVector>
// Get joint angles for all joints in a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<JointAngle, EcRealVector>
(
const EcU32 manipulatorIndex,
EcRealVector& value
) const;

Set/Get a Single Joint Position

The following methods can be used to set or get a single joint position on a single manipulator.

//------------------------------------------------------------------------------
// setParam<JointAngle, EcReal>
// Set a joint angle for a single joint in a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<JointAngle, EcReal>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
const EcReal& value
);
//------------------------------------------------------------------------------
// getParam<JointAngle, EcReal>
// Get a joint angle for a single joint in a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<JointAngle, EcReal>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcReal& value
) const;

Set/Get Multiple Joint Positions for Selected Manipulator-Links Simultaniously

The following methods allow setting and getting a vector joint values based on an input vector of manipulator and link index pairs.

typedef EcU32U32PairVector EcManipLinkIndexPairVector;
//------------------------------------------------------------------------------
// setParam<JointAngle, EcRealVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<JointAngle, EcRealVector>
(
const EcManipLinkIndexPairVector& manipLinkIndices,
const EcRealVector& jointAngleValues
);
//------------------------------------------------------------------------------
// getParam<JointAngle, EcRealVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<JointAngle, EcRealVector>
(
const EcManipLinkIndexPairVector& manipLinkIndices,
EcRealVector& jointAngleValues
) const;

JointController

The Ec::JointController parameter can be used to set and get the joint controller system container (EcJointControllerSystemContainer). See EcSystemSimulation::setJointControllerSystemContainer.

//------------------------------------------------------------------------------
// setParam<JointController, EcJointControllerSystemContainer>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<JointController, EcJointControllerSystemContainer>
(
);
//------------------------------------------------------------------------------
// getParam<JointController, EcJointControllerSystemContainer>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<JointController, EcJointControllerSystemContainer>
(
) const;
//------------------------------------------------------------------------------
// paramPtr<JointController, EcJointControllerSystemContainer>
//------------------------------------------------------------------------------
const EcJointControllerSystemContainer* Ec::Plugin::paramPtr<JointController, EcJointControllerSystemContainer>
(
) const;

JointVelocity

The Ec::JointVelocity parameter provides a way to specify or retrieve the velocity at which the joint moves when going from the current/actual location to the desired/calculated location. The arguements manipulatorIndex and subIndex below correspond to the manipulator and link indices respectively.

//------------------------------------------------------------------------------
// setParam<JointVelocity, EcRealVectorVector>
// Set the current joint velocity for all joints in all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<JointVelocity, EcRealVectorVector>
(
const EcRealVectorVector& value
);
//------------------------------------------------------------------------------
// getParam<JointVelocity, EcRealVectorVector>
// Get the current joint velocity for all joints in all manipulators.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<JointVelocity, EcRealVectorVector>
(
) const;
//------------------------------------------------------------------------------
// setParam<JointVelocity, EcRealVector>
// Set joint velocities for all joints in a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<JointVelocity, EcRealVector>
(
const EcU32 manipulatorIndex,
const EcRealVector& value
);
//------------------------------------------------------------------------------
// getParam<JointVelocity, EcRealVector>
// Get joint velocities for all joints in a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<JointVelocity, EcRealVector>
(
const EcU32 manipulatorIndex,
EcRealVector& value
) const;
//------------------------------------------------------------------------------
// setParam<JointVelocity, EcReal>
// Set joint velocity for a single joint in a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<JointVelocity, EcReal>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
const EcReal& value
);
//------------------------------------------------------------------------------
// getParam<JointVelocity, EcReal>
// Get joint velocity for a single joint in a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<JointVelocity, EcReal>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcReal& value
) const;

Manipulator

Ec::Manipulator provides access to the vector of manipulators in the system and their links.

Get the EcIndividualManipulatorVector

The following method can be used to get a pointer to the vector of manipulators in the system.

Note
The Simulation Mutex should be locked prior to getting the pointer and released immediately after the pointer is no longer needed.
//------------------------------------------------------------------------------
// paramPtr<Manipulator, EcIndividualManipulatorVector>
// gets a pointer to the vector of manipulators
//------------------------------------------------------------------------------
Plugin::paramPtr<Manipulator, EcIndividualManipulatorVector>
(
) const;

Get an Existing Manipulator

A manipulator object (EcIndividualManipulator) can be retrieved by index or by label using the following methods.

//------------------------------------------------------------------------------
// getParam<Manipulator, EcIndividualManipulator>
// gets the manipulator at the provided index.
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<Manipulator, EcIndividualManipulator>
(
const EcU32 manipulatorIndex,
) const;
//------------------------------------------------------------------------------
// getParam<Manipulator, EcIndividualManipulator>
// this method gets the first manipulator with the label manipLabel
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<Manipulator, EcIndividualManipulator>
(
const EcString& manipLabel,
) const;

Add a Manipulator

The following method can be used to add a new manipulator to the simulation.

//------------------------------------------------------------------------------
// setParam<Manipulator, EcIndividualManipulator>
// This version is used to add a new manipulator
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<Manipulator, EcIndividualManipulator>
(
);

Delete or Clone a Manipulator

The following method can be used to delete or clone a manipulator based on the value arguement. If value == 0 then the manipulator at manipulatorIndex is deleted, else the manipulator is cloned. A cloned manipulator is a reference of the original.

//------------------------------------------------------------------------------
// setParam<Manipulator, EcU32>
// This version is used to clone or delete a manipulator
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<Manipulator, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32& value
);

Get a Manipulator Link

//------------------------------------------------------------------------------
// getParam<Manipulator, EcManipulatorLink>
// gets the selected manipulator link
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<Manipulator, EcManipulatorLink>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

Set/Get Manipulator and Link Labels

The following methods are used to set or get the labels of manipulators and links.

//------------------------------------------------------------------------------
// getParam<Manipulator, EcStringVector>
// gets a vector of labels for the manipulators in the system
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<Manipulator, EcStringVector>
(
) const;
//------------------------------------------------------------------------------
// getParam<Manipulator, EcStringVector>
// gets a vector of the manipulator link labels
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<Manipulator, EcStringVector>
(
const EcU32 manipulatorIndex,
) const;
//------------------------------------------------------------------------------
// getParam<Manipulator, EcString>
// gets the manipulator's label
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<Manipulator, EcString>
(
const EcU32 manipulatorIndex,
EcString& value
) const;
//------------------------------------------------------------------------------
// setParam<Manipulator, EcString >
// This version is to change the manipulator label
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<Manipulator, EcString>
(
const EcU32 manipulatorIndex,
const EcString& newLabel
);
//------------------------------------------------------------------------------
// getParam<Manipulator, EcString>
// gets the manipulator link label
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<Manipulator, EcString>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
EcString& value
) const;

Set/Get the Active Manipulator

The following methods are used to set or get the active manipulator index.

//------------------------------------------------------------------------------
// setParam<Manipulator, EcU32>
// This version is used to set active manipulator
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<Manipulator, EcU32>
(
const EcU32& value
);
//------------------------------------------------------------------------------
// getParam<Manipulator, EcU32>
// This version is used to get active manipulator
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<Manipulator, EcU32>
(
EcU32& value
) const;

Get the Number of Manipulators

The following method returns the number of manipulators in the system.

//------------------------------------------------------------------------------
// param<Manipulator, EcU32>
// returns the number of manipulators
//------------------------------------------------------------------------------
const EcU32 Plugin::param<Manipulator, EcU32>
(
) const;

ManipulatorSystemConfiguration

This parameter is used to set/get the manipulator system configuration, which currently encapsulates the manipulator attachment map (EcManipulatorAttachmentMap) and collision exclusion map (EcSystemCollisionExclusionMap).

//------------------------------------------------------------------------------
// getParam<ManipulatorSystemConfiguration, EcManipulatorSystemConfiguration>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ManipulatorSystemConfiguration, EcManipulatorSystemConfiguration>
(
) const;
//------------------------------------------------------------------------------
// setParam<ManipulatorSystemConfiguration, EcManipulatorSystemConfiguration>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ManipulatorSystemConfiguration, EcManipulatorSystemConfiguration>
(
);

ManipulatorGraspingModule

Ec::ManipulatorGraspingModule can be used to set and get the manipulator grasping module vector.

//------------------------------------------------------------------------------
// setParam<ManipulatorGraspingModule, EcManipulatorGraspingModuleVector>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<ManipulatorGraspingModule, EcManipulatorGraspingModuleVector>
(
);
//------------------------------------------------------------------------------
// getParam<ManipulatorGraspingModule, EcManipulatorGraspingModuleVector>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<ManipulatorGraspingModule, EcManipulatorGraspingModuleVector>
(
) const;
//------------------------------------------------------------------------------
// paramPtr<ManipulatorGraspingModule, EcManipulatorGraspingModuleVector>
//------------------------------------------------------------------------------
Plugin::paramPtr<ManipulatorGraspingModule, EcManipulatorGraspingModuleVector>
(
) const;

ManipulatorLinkProps

The Ec::ManipulatorLinkProps parameter is used to set the properties of a link in the manipulator system based on the manipulator index (manipulatorIndex) and link index (subIndex) provided.

//------------------------------------------------------------------------------
// setParam<ManipulatorLinkProps, EcManipulatorLink>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<ManipulatorLinkProps, EcManipulatorLink>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
const EcManipulatorLink& value
);

MeasuredForce

Ec::MeasuredForce is used to set and get a description of the measured forces (EcManipulatorSensorForce) from sensors on a manipulator.

//------------------------------------------------------------------------------
// setParam<MeasuredForce, EcManipulatorSensorForce>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<MeasuredForce, EcManipulatorSensorForce>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<MeasuredForce, EcManipulatorSensorForce>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<MeasuredForce, EcManipulatorSensorForce>
(
const EcU32 manipulatorIndex,
) const;

NamedFrames

Ec::NamedFrames is used to set and get the named frames (EcNamedFrames) that are stored in each manipulator link or at the manipulator system level.

Set/Get all Named Frames attached to a Manipulator Link

The following methods can be used to set/get the named frames defined relative to a manipulator link primary frame. See EcManipulatorLink::setNamedFrames and EcManipulatorLink::namedFrames.

//------------------------------------------------------------------------------
// setParam<EcNamedFrame, EcNamedFrames>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<NamedFrames, EcNamedFrames>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
const EcNamedFrames& value
);
//------------------------------------------------------------------------------
// getParam<EcNamedFrame, EcNamedFrames>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<NamedFrames, EcNamedFrames>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

Set/Get a Named Frame attached to a Manipulator Link

The following methods can be used to set/get a specific named frame using a string name (key) on a manipulator link defined by (manipulatorIndex, linkIndex). The methods return true if the operation was successful. See EcManipulatorLink::setNamedFrames and EcManipulatorLink::namedFrames.

//------------------------------------------------------------------------------
// setParam<NamedFrames, EcCoordinateSystemTransformation>
// set a named frame at the manipulator link level
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<NamedFrames, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 linkIndex,
const EcString& key,
);
//------------------------------------------------------------------------------
// getParam<NamedFrames, EcCoordinateSystemTransformation>
// get a named frame at the manipulator link level
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<NamedFrames, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 linkIndex,
const EcString& key,
) const;

Set/Get all Named Frames at the Manipulator System Level

The following methods can be used to set/get the named frames that are defined relative to the manipulator system origin. See EcManipulatorSystem::setNamedFrames and EcManipulatorSystem::namedFrames.

//------------------------------------------------------------------------------
// setParam<EcNamedFrame, EcNamedFrames>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<NamedFrames, EcNamedFrames>
(
const EcNamedFrames& value
);
//------------------------------------------------------------------------------
// getParam<EcNamedFrame, EcNamedFrames>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<NamedFrames, EcNamedFrames>
(
) const;

Set/Get a Named Frame at the Manipulator System Level

The following methods can be used to set/get a named frame relative to the manipulator system origin based on the frame name (key). See EcManipulatorSystem::setNamedFrames and EcManipulatorSystem::namedFrames.

//------------------------------------------------------------------------------
// setParam<NamedFrames, EcCoordinateSystemTransformation>
// set a named frame at the manipulator system level
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<NamedFrames, EcCoordinateSystemTransformation>
(
const EcString& key,
)
//------------------------------------------------------------------------------
// getParam<NamedFrames, EcCoordinateSystemTransformation>
// get a named frame at the manipulator system level
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<NamedFrames, EcCoordinateSystemTransformation>
(
const EcString& key,
) const

NamedFramesInSystem

Ec::NamedFramesInSystem is used to get the current system coordinate frame of named frames (EcNamedFrames) defined relative to manipulator link.

Get Current all Named Frames of a Manipulator Link in System Coordinates

The following method can be used to get the named frames of a manipulator link (manipulatorIndex, linkIndex) in system coordinates. See EcManipulatorLink::primaryFrameInSystem and EcManipulatorLink::namedFrames.

//------------------------------------------------------------------------------
// getParam<NamedFramesInSystem, EcNamedFrames>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<NamedFramesInSystem, EcNamedFrames>
(
const EcU32 manipulatorIndex,
const EcU32 linkIndex,
) const;

Get a Named Frame of a Manipulator Link in System Coordinates

The following method can be used to get a named frame (key) of a manipulator link (manipulatorIndex, linkIndex) in system coordinates. See EcManipulatorLink::primaryFrameInSystem and EcManipulatorLink::namedFrames.

//------------------------------------------------------------------------------
// getParam<NamedFramesInSystem, EcCoordinateSystemTransformation>
// get a named frame at the manipulator link level
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<NamedFramesInSystem, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 linkIndex,
const EcString& key,
) const;

OutputWriterVector

Ec::OutputWriterVector is used to set and get the objects used to write the simulation outputs to different file formats.

//------------------------------------------------------------------------------
// setParam<OutputWriterVector, EcOutputWriterVector>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<OutputWriterVector, EcOutputWriterVector>
(
const EcOutputWriterVector& value
);
//------------------------------------------------------------------------------
// getParam<OutputWriterVector, EcOutputWriterVector>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<OutputWriterVector, EcOutputWriterVector>
(
) const;

PositionControlSystem DEPRECATED

Note
This parameter is deprecated, use the ControlSystem parameter instead.

Ec::PositionControlSystem is used to set and get the position control container or system from the simulation.

//------------------------------------------------------------------------------
// setParam<PositionControlSystem, EcPositionControlContainer>
// DEPRECATED
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<PositionControlSystem, EcPositionControlContainer>
(
);
//------------------------------------------------------------------------------
// getParam<PositionControlSystem, EcPositionControlContainer>
// DEPRECATED
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<PositionControlSystem, EcPositionControlContainer>
(
) const;
//------------------------------------------------------------------------------
// paramPtr<PositionControlSystem, EcPositionControlContainer>
// Callers should acquire the SimulationMutex lock beforehand if using the paramPtr accessor.
// DEPRECATED
//------------------------------------------------------------------------------
Plugin::paramPtr<PositionControlSystem, EcPositionControlContainer>
(
) const;
//------------------------------------------------------------------------------
// setParam<PositionControlSystem, EcPositionControlSystem>
// DEPRECATED
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<PositionControlSystem, EcPositionControlSystem>
(
);
//------------------------------------------------------------------------------
// getParam<PositionControlSystem, EcPositionControlSystem>
// DEPRECATED
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<PositionControlSystem, EcPositionControlSystem>
(
) const;
//------------------------------------------------------------------------------
// paramPtr<PositionControlSystem, EcPositionControlSystem>
// Callers should acquire the SimulationMutex lock beforehand if using the paramPtr accessor.
// DEPRECATED
//------------------------------------------------------------------------------
Plugin::paramPtr<PositionControlSystem, EcPositionControlSystem>
(
) const;

PrimaryFrame

Every link on every manipulator in the system has a rigidly attached 3D frame (EcCoordinateSystemTransformation) called the Primary Frame. Most link quantities (mass properties, end-effector attachment, and so forth) are defined with respect to the primary frame. If you know the position and orientation of the Primary Frame, you can determine the position and orientation of the link. The Primary Frame is rigidly connected to the DH Frame (see DhFrame).

//------------------------------------------------------------------------------
// getParam<PrimaryFrame, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<PrimaryFrame, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 subIndex,
) const;

ProfiledEndEffectors

Sets some end-effectors to follow a profiled trajectory. If indices is not empty, the control mode will automatically be set to PROFILED_POSITION and the speed factors of the end-effectors specified by indices will be changed to 0 (no limit). If indices is empty, the control mode will be set back to POSITION_CONTROL and the speed factors of all end-effectors will be set to 1.

//------------------------------------------------------------------------------
// setParam<ProfiledEndEffectors, EcU32Vector>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<ProfiledEndEffectors, EcU32Vector>
(
const EcU32 manipulatorIndex,
const EcU32Vector& value
);

PropagationResults

Ec::PropagationResults gets the result of collision detection through the EcPropagationResultData object. See the Status Plugin page for a display example of the propagation results in Actin Viewer.

//------------------------------------------------------------------------------
// getParam<PropagationResults, EcPropagationResultDataVector>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<PropagationResults, EcPropagationResultDataVector>
(
) const;
//------------------------------------------------------------------------------
// getParam<PropagationResults, EcPropagationResultData>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<PropagationResults, EcPropagationResultData>
(
const EcU32 manipulatorIndex,
) const;

SimRunState

Accesses the current simulation state. Can be one of the Ec::SimulationRunState values including: Ec::SimulationStopped, Ec::SimulationRunning, or Ec::SimulationPaused.

//------------------------------------------------------------------------------
// setParam<SimRunState, EcManipulatorSystemState>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<SimRunState, SimulationRunState>
(
const SimulationRunState& value
);
//------------------------------------------------------------------------------
// getParam<SimRunState, SimulationRunState>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<SimRunState, SimulationRunState>
(
) const;
//------------------------------------------------------------------------------
// param<SimRunState, SimulationRunState>
//------------------------------------------------------------------------------
Plugin::param<SimRunState, SimulationRunState>
(
) const;

SimulationThreadUpdateRate

Sets and gets the simulation thread update rate in Hz. The simulation thread update rate determines the rate at which EcIODataBroker::runSimulationCycle is called. This determines the rate at which the Ec::IOBuffer is updated by the EcIODataBroker. See EcIODataBroker::setSimulationThreadUpdateRate.

//------------------------------------------------------------------------------
// Ec::Plugin::setParam<SimulationThreadUpdateRate, EcReal>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<SimulationThreadUpdateRate, EcReal>
(
const EcReal& value
);
//------------------------------------------------------------------------------
// Ec::Plugin::param<SimulationThreadUpdateRate, EcReal>
//------------------------------------------------------------------------------
const EcReal Plugin::param<SimulationThreadUpdateRate, EcReal>
(
) const;

SimulationMutex

Provides thread-safe access to simulation components handled by the Ec::IOBuffer. This is required of any component retrieved via the Ec::Plugin::paramPtr accessor. It provides direct access to modifying the simulation.

Note
The caller of these methods should return the lock (let it go out of scope) as soon as possible. Holding onto a simulation lock will greatly degrade performance of the simulation. If the lock is needed for an extended period of time, consider using the corresponding Ec::Plugin::getParam method instead.
//------------------------------------------------------------------------------
// getParam<SimulationMutex, EcSharedMutexLock>
// Retrieve a unique, exclusive write lock.
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<SimulationMutex,EcSharedMutexLock>
(
) const;
//------------------------------------------------------------------------------
// getParam<SimulationMutex, EcSharedMutexSharedLock>
// Retrieve a shared read lock. Multiple threads may acquire this lock simultaneously to retrieve parameter information from the simulation.
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<SimulationMutex,EcSharedMutexSharedLock>
(
) const;

SimulationReset

The Ec::SimulationReset parameter is used to reset the simulation to the initial state and configuration defined by the Home State. Set the boolean argument value to true to reset the desired end-effector placements in addition to the simulation. If value is false then only the simulation state will be reset. See Ec::IOBuffer::resetSimulation.

//------------------------------------------------------------------------------
// setParam<SimulationReset, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<SimulationReset,EcBoolean>
(
const EcBoolean& value
);

SimulationTime

Ec::SimulationTime is used to get the current simulation time in seconds. See EcManipulatorSystemState::time.

//------------------------------------------------------------------------------
// getParam<SimulationTime, EcTime>
// get the current simulation time
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<SimulationTime, EcTime>
(
EcTime& value //time
) const;

SpeedFactor

The Ec::SpeedFactor parameter sets the speed factor for all end-effector sets as well as the underlying controller. The value must be positive. Use value greater than 1 to speed up or value less than 1 to slow down the whole robot. See EcVelocityController::speedFactor.

//------------------------------------------------------------------------------
// getParam<SpeedFactor, EcReal>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<SpeedFactor, EcReal>
(
const EcU32 manipulatorIndex,
EcReal& value
) const;
//------------------------------------------------------------------------------
// setParam<SpeedFactor, EcReal>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<SpeedFactor, EcReal>
(
const EcU32 manipulatorIndex,
const EcReal& value
);

State

Ec::State is used to access the current state of the manipulators in the simulation.

Set/Get Manipulator System State

//------------------------------------------------------------------------------
// setParam<State, EcManipulatorSystemState>
// Sets the entire state of the simulation.
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<State, EcManipulatorSystemState>
(
);
//------------------------------------------------------------------------------
// getParam<State, EcManipulatorSystemState>
// Gets the entire state of the simulation
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<State, EcManipulatorSystemState>
(
) const;
//------------------------------------------------------------------------------
// param<State, EcManipulatorSystemState>
// Retrieves a const handle to the current state of the simulation
//------------------------------------------------------------------------------
Plugin::param<State, EcManipulatorSystemState>
(
) const;

Set/Get Position State of a Manipulator

The following methods can be used to set and get the position state information for a single manipulator through EcPositionState.

//------------------------------------------------------------------------------
// setParam<State, EcPositionState>
// Sets the positional state information for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<State, EcPositionState>
(
const EcU32 manipulatorIndex,
const EcPositionState& value
);
//------------------------------------------------------------------------------
// getParam<State, EcPositionState>
// Gets the positional state information for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<State, EcPositionState>
(
const EcU32 manipulatorIndex,
) const;

Set/Get Velocity State of a Manipulator

The following methods can be used to set and get the velocity state information for a single manipulator through EcVelocityState.

//------------------------------------------------------------------------------
// setParam<State, EcVelocityState>
// Sets the velocity state information for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<State, EcVelocityState>
(
const EcU32 manipulatorIndex,
const EcVelocityState& value
);
//------------------------------------------------------------------------------
// getParam<State, EcVelocityState>
// Gets the velocity state information for a single manipulator.
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<State, EcVelocityState>
(
const EcU32 manipulatorIndex,
) const;

StatedSystem

Ec::StatedSystem provides direct access to the simulation’s manipulator system and state object defined by EcStatedSystem.

//------------------------------------------------------------------------------
// setParam<StatedSystem, EcStatedSystem>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<StatedSystem, EcStatedSystem>
(
const EcStatedSystem& value
);
//------------------------------------------------------------------------------
// paramPtr<StatedSystem, EcStatedSystem>
// Retrieves a const pointer to the current StatedSystem of the simulation
// Callers should acquire the SimulationMutex lock beforehand.
//------------------------------------------------------------------------------
Plugin::paramPtr<StatedSystem, EcStatedSystem>
(
) const;

StaticCollisionExclusionMap

Ec::StaticCollisionExclusionMap sets and gets the static collision exclusion map. This map should not change frequently. To modify the collision exclusions at runtime please use the dynamic collision exclusion map accessor methods provided by CollisionExclusionMap.

//------------------------------------------------------------------------------
// setParam<StaticCollisionExclusionMap, EcSystemCollisionExclusionMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<StaticCollisionExclusionMap, EcSystemCollisionExclusionMap>
(
);
//------------------------------------------------------------------------------
// getParam<StaticCollisionExclusionMap, EcSystemCollisionExclusionMap>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<StaticCollisionExclusionMap, EcSystemCollisionExclusionMap>
(
) const;

StopMotion

Ec::StopMotion can be used to stop the simulation and force the joint velocities to zero. This calls Ec::IOBuffer::stopMotion().

//------------------------------------------------------------------------------
// setParam<StopMotion>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<StopMotion, EcBoolean>
(
const EcU32 manipulatorIndex,
const EcBoolean& value
);

SystemDataCapture

Ec::SystemDataCapture is used to set and get the system data capture object (EcSystemDataCapture) for storage.

//------------------------------------------------------------------------------
// setParam<SystemDataCapture, EcSystemDataCapture>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<SystemDataCapture, EcSystemDataCapture>
(
const EcSystemDataCapture& value
);
//------------------------------------------------------------------------------
// getParam<SystemDataCapture, EcSystemDataCapture>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<SystemDataCapture, EcSystemDataCapture>
(
) const;

SystemEnvironment

Ec::SystemEnvironment sets and gets the system environment data object defined by EcSystemEnvironment. This object includes the gravity vector used for dynamic simulation.

//------------------------------------------------------------------------------
// setParam<SystemEnvironment, EcSystemEnvironment>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<SystemEnvironment, EcSystemEnvironment>
(
const EcSystemEnvironment& value
);
//------------------------------------------------------------------------------
// getParam<SystemEnvironment, EcSystemEnvironment>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<SystemEnvironment, EcSystemEnvironment>
(
) const;

SystemSimulation

Ec::SystemSimulation provides direct access to the system simulation object (EcSystemSimulation), which contains a simulation environment for a stated system and its position control system.

//------------------------------------------------------------------------------
// setParam<SystemSimulation, EcSystemSimulation>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<SystemSimulation, EcSystemSimulation>
(
const EcSystemSimulation& value
);
//------------------------------------------------------------------------------
// getParam<SystemSimulation, EcSystemSimulation>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<SystemSimulation, EcSystemSimulation>
(
) const;
//------------------------------------------------------------------------------
// paramPtr<SystemSimulation, EcSystemSimulation>
// Retrieves a const pointer to the simulation
// Callers should acquire the SimulationMutex lock beforehand.
//------------------------------------------------------------------------------
Plugin::paramPtr<SystemSimulation, EcSystemSimulation>
(
) const;

ToolOffset

Get the Number of Tool Offsets for a Manipulator

Get the number of tool offsets stored for the a manipulator (manipulatorIndex).

//------------------------------------------------------------------------------
// getParam<ToolOffset, EcSizeT>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ToolOffset, EcSizeT>
(
const EcU32 manipulatorIndex,
EcSizeT& value
) const;

Set/Get All Tool Offset Transformations for a Manipulator

The following methods can be used to set or get all tool offset transformations for a given manipulator (manipulatorIndex). The methods below return false if the manipulator index is invalid.

//------------------------------------------------------------------------------
// setParam<ToolOffset, EcCoordinateSystemTransformationVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ToolOffset, EcCoordinateSystemTransformationVector>
(
const EcU32 manipulatorIndex,
);
//------------------------------------------------------------------------------
// getParam<ToolOffset, EcCoordinateSystemTransformationVector>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ToolOffset, EcCoordinateSystemTransformationVector>
(
const EcU32 manipulatorIndex,
) const;

Set/Get a Tool Offset Transformation of a Manipulator

The Ec::ToolOffset parameter is used to set and get tool offsets (as an EcCoordinateSystemTransformation) given a tool index (toolOffsetIndex) for a given manipulator (manipulatorIndex). The methods below return false if the manipulator index or tool index is invalid.

//------------------------------------------------------------------------------
// getParam<ToolOffset, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<ToolOffset, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 toolOffsetIndex,
) const;
//------------------------------------------------------------------------------
// setParam<ToolOffset, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<ToolOffset, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 toolOffsetIndex,
);

Set/Get the Active Tool Offset by Index for a Motion Constraint

The following methods can be used to set or get the index (toolOffsetIndex) of a given manipulator's motion constraint defined by (manipulatorIndex, endEffectorSetIndex, endEffectorIndex). The methods below return false if the manipulator index is invalid.

//------------------------------------------------------------------------------
// setParam<ToolOffset, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ToolOffset, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32 endEffectorSetIndex,
const EcU32 endEffectorIndex,
const EcU32& toolOffsetIndex
);
//------------------------------------------------------------------------------
// getParam<ToolOffset, EcU32>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ToolOffset, EcU32>
(
const EcU32 manipulatorIndex,
const EcU32 endEffectorSetIndex,
const EcU32 endEffectorIndex,
EcU32& toolOffsetIndex
) const;

Set/Get the Active Tool Offset Transformation for a Motion Constraint

The Ec::ToolOffset parameter can also be used to set and get Active tool offsets (as an EcCoordinateSystemTransformation) given a motion constraint set "endEffector set" index (endEffectorSetIndex) and constraint "end effector" index (endEffectorIndex) for a given manipulator (manipulatorIndex). The methods below return false if the manipulator index or tool index is invalid.

//------------------------------------------------------------------------------
// setParam<ToolOffset, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::setParam<ToolOffset, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 endEffectorSetIndex,
const EcU32 endEffectorIndex,
);
//------------------------------------------------------------------------------
// getParam<ToolOffset, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Ec::Plugin::getParam<ToolOffset, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 endEffectorSetIndex,
const EcU32 endEffectorIndex,
) const;

ToolOffsetFixEE

Provides plugin access to the Ec::IOBuffer::setToolOffsetFixEE method.

//------------------------------------------------------------------------------
// setParam<ToolOffsetFixEE, EcCoordinateSystemTransformation>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<ToolOffsetFixEE, EcCoordinateSystemTransformation>
(
const EcU32 manipulatorIndex,
const EcU32 toolOffsetIndex,
);

ViewerParameters

Gets and sets a description of parameters through the EcViewerParameters object to control the properties of the GUI and rendering window.

//------------------------------------------------------------------------------
// setParam<ViewerParameters, EcViewerParameters>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<ViewerParameters, EcViewerParameters>
(
const EcViewerParameters& value
);
//------------------------------------------------------------------------------
// getParam<ViewerParameters, EcViewerParameters>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<ViewerParameters, EcViewerParameters>
(
) const;
//------------------------------------------------------------------------------
// param<ViewerParameters, EcViewerParameters>
//------------------------------------------------------------------------------
Plugin::param<ViewerParameters, EcViewerParameters>
(
) const;

VirtualActive

Set or get the Ec::VirtualActive flag that determines if the Virtual Manipulator System (ghost system) is active or not.

//------------------------------------------------------------------------------
// param<VirtualActive, EcBoolean>
//------------------------------------------------------------------------------
const EcBoolean Plugin::param<VirtualActive, EcBoolean>
(
) const;
//------------------------------------------------------------------------------
// setParam<VirtualActive, EcBoolean>
//------------------------------------------------------------------------------
EcBoolean Plugin::setParam<VirtualActive, EcBoolean>
(
const EcBoolean& value
);
//------------------------------------------------------------------------------
// getParam<VirtualManipulatorIndex, EcU32>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<VirtualManipulatorIndex, EcU32>
(
const EcU32 manipulatorIndex,
EcU32& value
) const;

VirtualManipulatorIndex

Gets the Virtual Manipulator Index corresponding to a manipulator index in the real system.

//------------------------------------------------------------------------------
// getParam<VirtualManipulatorIndex, EcU32>
//------------------------------------------------------------------------------
EcBoolean Plugin::getParam<VirtualManipulatorIndex, EcU32>
(
const EcU32 manipulatorIndex,
EcU32& value
) const;

WhatChanged

Ec::WhatChanged provides a mechanism to determine what internal values have changed during the last simulation time step. It is a bitwise set of flags which can be bits indicating what changed in the last time step. Consumers can use these flags to adjust behavior based on the change. Note that if the plugin is running at a different rate than the simulation, then there is no guarantee that all changes will be visible. The changed values are valid only until the next simulation time step is calculated.

//------------------------------------------------------------------------------
// param<WhatChanged, EcU32>
//------------------------------------------------------------------------------
const EcU32 Plugin::param<WhatChanged, EcU32>
(
) const;

Bits indicating what changed in the last timestep. Consumers can use these flags to adjust behavior based on the change. Note that if the plugin is running at a different rate than the simulation, then there is no guarantee that all changes will be visible. The changed values are valid only until the next simulation timestep is calculated.

Bits defined by Ec::BitFlagsEnum indicating what changed in the last timestep
Flag Bit Description
Ec::DesiredForceBit 0x001 Desired force change
Ec::DesiredPosBit 0x002 Desired end-effector change
Ec::DesiredVelBit 0x004 Desired velocity change
Ec::EESetBit 0x008 End-effector set change
Ec::StateBit 0x010 State change
Ec::ForceControlBit 0x020 Force control On/Off change
Ec::ForceSensorBit 0x040 Measured force change
Ec::EESetIndexBit 0x080 End-effector set index change
Ec::ForceControlDescriptorBit 0x100 Force descriptor index change
Ec::PositionControlSystemBit 0x200 Position control system change
Ec::ForceControlSystemBit 0x400 Force control system change
Ec::AttachmentMapBit 0x800 Change in attachment map
Ec::ControlModeBit 0x1000 Control mode change

Examples

Example Plugin

The following code blocks provide an example of a non-gui plugin derived from Ec::Plugin.

#ifndef examplePlugin_H_
#define examplePlugin_H_
//------------------------------------------------------------------------------
// Copyright (c) 2009-2013 Energid Technologies. All rights reserved.
//
//
//------------------------------------------------------------------------------
#include <fstream>
class examplePlugin : public Ec::Plugin
{
public:
(
);
(
);
(
);
(
);
(
);
void update
(
const EcReal time
);
protected:
std::ofstream m_out;
};
#endif // examplePlugin_H_
Example plugin header file
//------------------------------------------------------------------------------
// Copyright (c) 2008-2013 Energid Technologies. All rights reserved.
//
//
//------------------------------------------------------------------------------
// Default to building without Actin or boost support.
#ifndef EC_HAVE_ACTIN
# define EC_NO_ACTIN
# define EC_NO_BOOST
#endif
#include "examplePlugin.h"
// Required declaration to define entry point and parameters for this plugin.
using namespace Ec;
//-----------------------------------------------------------------------
// operator<<
// Convenience function to print a vector of joint values.
// Outputs processed joint values comma-separated on a single line.
//-----------------------------------------------------------------------
std::ostream &
operator<<
(
std::ostream& os,
const EcRealVector& vec
)
{
const EcSizeT num = vec.size();
if(num)
{
os << vec[0];
for (EcSizeT ii = 1; ii<num; ++ii)
{
os << ", " << vec[ii];
}
}
return os;
}
//-----------------------------------------------------------------------
// examplePlugin constructor
// Opens data logging file and sets base examplePlugin member variables.
// Called on plugin load.
//-----------------------------------------------------------------------
(
):
{
/* If we do not set an update period, then it will default to 0, which
means it will get called at the same rate as the simulation itself.
m_UpdatePeriodInMs = 20; // Run at 50Hz
*/
}
//-----------------------------------------------------------------------
// examplePlugin destructor
//-----------------------------------------------------------------------
(
)
{
if(m_out.is_open())
{
EcPrint(None) << "Closing down examplePlugin.\n";
}
// Unregister our extra output stream.
}
//-----------------------------------------------------------------------
// examplePlugin::init
// Initializes plugin before first use. Called right after the constructor.
//-----------------------------------------------------------------------
(
)
{
// Open up our file
m_out.open("examplePlugin_log.txt");
EcBoolean retVal = m_out.is_open();
if(retVal)
{
// By adding to our print handle, we are able to redirect all
// Energid messages to multiple locations.
// This will just go to our log file.
m_out << "examplePlugin init: direct output to one file.\n";
// This will go to results.txt, our log file and any other
// stream that has been added.
EcPrint(None) << "examplePlugin init: output to all streams.\n";
}
return retVal;
}
//-----------------------------------------------------------------------
// examplePlugin::reset
// Reinitialize examplePlugin. Called before a file is loaded the
// first time as well as when a new data file is loaded in the viewer.
//-----------------------------------------------------------------------
(
)
{
// Bail if we are unable to write out.
if(!m_out.is_open())
{
return EcFalse;
}
EcPrint(None) << "examplePlugin - reset called.\n";
return EcTrue;
}
//-----------------------------------------------------------------------
// examplePlugin::initState
// Provides a mechanism to modify the robotic simulation state before
// starting. Typically used to retrieve real hardware values from the
// robot to set the initial position and synchronize simulation to reality.
// Called right after file loading.
//-----------------------------------------------------------------------
(
)
{
if(!m_out.is_open())
{
return EcFalse;
}
EcPrint(None) << "initState called.\n";
// Just deal with the first manipulator
EcU32 manipId = 0;
EcRealVector jointCommands;
EcBoolean retVal = getParam<JointAngle>(manipId, jointCommands);
if(retVal)
{
// Create some new initial position.
EcReal val = jointCommands[manipId] + 1.0;
// Set the first joint
retVal &= setParam<JointAngle>(manipId, 0, val);
}
return retVal;
}
//-----------------------------------------------------------------------
// examplePlugin::update
// Gets called either at the simulation rate or at the specified rate
// depending on the value of m_UpdatePeriodInMs. Simulation values are
// retrieved using the plugin API getParam methods.
//-----------------------------------------------------------------------
void
(
const EcReal time
)
{
// Bail if we are unable to write out.
if(!m_out.is_open())
{
return;
}
EcRealVectorVector jointCommands;
// This method will retrieve all joint values for all manipulators
getParam<JointAngle>(jointCommands);
// If we wanted to just retrieve for a single manipulator we could
// have done this:
// EcRealVector jointCommands;
// getParam<JointAngle>(0, jointCommands); // 0 == manip index
//
// Many other options for setting and retrieving parameters are
// available. See <plugins/ecIOParams.h> for available types
for (EcSizeT ii = 0, size = jointCommands.size(); ii<size; ++ii)
{
EcPrint(None) << "Time " << time
<< " Manip " << ii
// Use our convenience operator<< to process vector.
<< ": " << jointCommands[ii] << std::endl;
}
}
Example plugin impelementation file

Example GUI Plugin

The following code blocks provide an example of a gui plugin derived from Ec::PluginGUI.

#ifndef exampleGUIPlugin_H_
#define exampleGUIPlugin_H_
//------------------------------------------------------------------------------
// Copyright (c) 2012-2013 Energid Technologies. All rights reserved.
//
//------------------------------------------------------------------------------
{
Q_OBJECT
protected:
(
);
(
);
(
);
protected Q_SLOTS:
void onActionButtonPressed(bool checked);
};
#endif // exampleGUIPlugin_H_
Example GUI plugin header file
//------------------------------------------------------------------------------
// Copyright (c) 2012-2013 Energid Technologies. All rights reserved.
//
//
//------------------------------------------------------------------------------
#include <QtWidgets/QPushButton>
#include <QtWidgets/QAction>
// Required declaration to define entry point and parameters for this plugin.
//------------------------------------------------------------------------------
(
):
Ec::PluginGUI()
{
}
//------------------------------------------------------------------------------
(
)
{
// As long as proper Qt parentage is applied to objects, everything
// should be cleaned up when this plugin is destroyed and we shouldn't
// need to explicitly delete anything. Objects that don't have this plugin
// as their parent (or no parent) can be added to the auto-cleanup list by
// using the following call:
//
// addAutoCleanup(QtObject*);
//
// These objects will be destroyed as part of the base-class destructor. Do
// not add objects to this list that will handled elsewhere, otherwise
// double-deletion may occur.
//
// QDockWidgets and QToolBars will be automatically handled when added with
// the PluginGUI methods (addToolBar, addDockWidget).
}
//------------------------------------------------------------------------------
// Initializes plugin before first use. Called right after the constructor.
//------------------------------------------------------------------------------
(
)
{
// Create a GUI button
QAction* action = new QAction(this);
action->setCheckable(true);
action->setObjectName(QString::fromUtf8("actionExample"));
action->setText(QString::fromUtf8("Press me"));
return addToToolBar(action) &&
connect(action, SIGNAL(toggled(bool)), SLOT(onActionButtonPressed(bool)));
}
//------------------------------------------------------------------------------
// Called when user presses button
//------------------------------------------------------------------------------
void
exampleGUIPlugin::onActionButtonPressed
(
bool checked
)
{
QAction* action = qobject_cast<QAction*>(sender());
if(action)
{
action->setText(QString::fromUtf8(checked ? "Unpress me" : "Press me"));
}
}
Example GUI plugin impelementation file

Example Usage for PluginGUI Params

This section provides a few examples for using the Plugin GUI parameters. Refer to viewerCore/ecPluginGUI.h for available enumerations
The code block below shows an example of setting the GuideFrame to a certain position in the UI.

//Get a pointer to myPlugin
Ec::Plugin* pPlugin = Ec::Plugin::getPlugin("myPlugin");
//Check that the pointer is valid
if(!pPlugin)
{
return;
}
//Get the coordinates of the actual EndEffector for a particular manipulator
pPlugin->getParam<Ec::ActualEndEffector, EcCoordinateSystemTransformation>(manipIndex, EeSetIndex, trans);
//Set the GuideFrame to the actual EndEffector position
pPlugin->setParam<Ec::GuideFrame>(trans);
Example usage of the Ec::GuideFrame using setParam

The code block below shows using the DisplayMask to control the various display properties of the simulation on the render window. The various parameters that can be controlled are, displaying bounding boxes, mass property ellipsoids, guideframe, dragger etc.

//Get a pointer to myPlugin
Ec::Plugin* pPlugin = Ec::Plugin::getPlugin("myPlugin");
//Check that the pointer is valid
if(!pPlugin)
{
return;
}
//Turn on the Guide Axis
pPlugin->setParam<Ec::DisplayMask>(EcRenderTypes::GuideAxis, EcTrue);
//Display the bounding volumes
pPlugin->setParam<Ec::DisplayMask>(EcRenderTypes::BoundingVolume, EcTrue);
//Display the AABb Boxes
pPlugin->setParam<Ec::DisplayMask>(EcRenderTypes::AxisAlignedBB, EcTrue);
//If the render window has a dragger created and you want to display the Dragger
pPlugin->setParam<Ec::DisplayMask>(EcRenderTypes::Dragger, EcTrue);
//Turn on VirtualManipulator display mask
pPlugin->setParam<Ec::DisplayMask>(EcRenderTypes::VirtualManipulator, EcTrue);
Example usage of the PluginGUI params to change the "Display Attributes" of the render window

The code block below shows using Plugin GUI parameters to set an active Manipulator, active EndEffectorSet Index, save and restore System Execution State

//Select a different manipulator as active manipulator and
/set an activeEESet
//Get a pointer to myPlugin
Ec::Plugin* pPlugin = Ec::Plugin::getPlugin("myPlugin");
// Check that the pointer is valid
if(!pPlugin)
{
return;
}
//Here getCurrentManipSelection, could return the manipulator index selected in UI layer
//or could be a value that is given from another interface layer
EcU32 activeManipIndex = getCurrentManipSelection();
//Here getCurrentManipSelection, could return the EeSet index selected in UI layer
//or could be a value that is given from another interface layer for a given manipulator index
EcU32 activeEESetIndex = getCurrentEESetSelection(activeManipIndex);
// set the system to not ready so it will not change the data being used currently.
pPlugin->setParam<Ec::SystemReady>(EcFalse);
//Before updating the simulation parameters, save the current
//state of simulation, set simulation to stopped state, make
//the changes and restore the simulation state
EcU32 runState = m_pPlugin->param<Ec::SimRunState, Ec::SimulationRunState>();
if (activeManipIndex != -1)
{
EcU32 selectedEE = 0;
pPlugin->setParam<Ec::SelectedArm>(activeManipIndex);
pPlugin->setParam<Ec::EndEffectorSet>(activeManipIndex, activeEESetIndex);
pPlugin->setParam<Ec::SelectedEndEffector>(selectedEE);
}
//Restore the system state
pPlugin->setParam<Ec::SystemReady>(EcTrue);
pPlugin->setParam<Ec::SimRunState>(Ec::SimulationRunState(runState));
Example usage of the PluginGUI params to change the active Manipulator, EndEffectorSet Index and the EndEffector

The code block below shows using Plugin GUI parameters to set certain "Viewer Attributes" like shadow

// Get a pointer to myPlugin
Ec::Plugin* pPlugin = Ec::Plugin::getPlugin("myPlugin");
// Check that the pointer is valid
if(!pPlugin)
{
return;
}
//Turn on the shadows in the render window
pPlugin->setParam<Ec::ViewerAttribute>(EcRenderTypes::Shadows, EcTrue);
//Turn on the lighting in the render window
pPlugin->setParam<Ec::ViewerAttribute>(EcRenderTypes::Lighting, EcTrue);
//Turn on the texture to be rendered
pPlugin->setParam<Ec::ViewerAttribute>(EcRenderTypes::Texture, EcTrue);
Example usage of the PluginGUI params to enable shadow, lighting and texture mode in the render window

The code block below shows using Plugin GUI parameters to set "Visualization Parameters" like eyepoint etc

// Get a pointer to myPlugin
Ec::Plugin* pPlugin = Ec::Plugin::getPlugin("myPlugin");
// Check that the pointer is valid
if(!pPlugin)
{
return;
}
pov.setEyepoint(EcVector(0.0, -6.0, 15.0));
pov.setCenterOfInterest(EcVector(0.0,1.0,0.0));
pov.setFieldOfView(0.15);
vizParams.setPovParameters(pov);
Example usage of the PluginGUI param to set Visualization Parameters
Created by Energid Technologies www.energid.com
Copyright © 2016 Energid. All trademarks mentioned in this document are property of their respective owners.