Class Mechanism
A mechanism is a GraphicComponent that a number of joints controlling the movement of a number of links. A robot is the archetypal mechanism in RobotStudio, but it is not the only kind.
Inherited Members
Namespace: ABB.Robotics.RobotStudio.Stations
Assembly: ABB.Robotics.RobotStudio.Stations.dll
Syntax
sistent("MechanismInstance")]
public class Mechanism : GraphicComponent, IHasTransform, IHasFrames, IAttachableChild, ISupportCopy, IGfxObject, IHasGraphicComponents
Constructors
Mechanism(PimDocument)
Declaration
protected Mechanism(PimDocument doc)
Parameters
Type | Name | Description |
---|---|---|
RobotStudio.API.Persistence.PimDocument | doc |
Fields
_jointValues
Declaration
Compliant(false)]
[Undoable]
[Persistent("JointValues", Convert = PimConvert.NoConversion)]
protected double[] _jointValues
Field Value
Type | Description |
---|---|
Double[] |
_numJoints
Declaration
Compliant(false)]
[Persistent("NumJoints")]
[Undoable]
protected int _numJoints
Field Value
Type | Description |
---|---|
Int32 |
Properties
AdditionalComponents
Gets a GraphicComponentCollection that contains child components that are not mechanism links.
Declaration
public GraphicComponentCollection AdditionalComponents { get; }
Property Value
Type | Description |
---|---|
GraphicComponentCollection |
GraphicComponents
Gets a GraphicComponentCollection that contains all the links of the mechanism.
Declaration
public GraphicComponentCollection GraphicComponents { get; }
Property Value
Type | Description |
---|---|
GraphicComponentCollection |
KinematicsFlags
Returns the kinematic type and other properties for a Mechanism of type Robot
Declaration
public KinematicsFlags KinematicsFlags { get; }
Property Value
Type | Description |
---|---|
KinematicsFlags |
Mass
The mass of the mechanism. Used when the mechanism is used as a tool.
Declaration
public double Mass { get; }
Property Value
Type | Description |
---|---|
Double |
MechanismType
Gets the type.
Declaration
public MechanismType MechanismType { get; }
Property Value
Type | Description |
---|---|
MechanismType |
ModelBaseFrame
Returns the nominal base frame of this model
Declaration
public Matrix4 ModelBaseFrame { get; }
Property Value
Type | Description |
---|---|
Matrix4 |
ModelName
Gets the name of the model.
Declaration
public string ModelName { get; }
Property Value
Type | Description |
---|---|
String |
MultiAxisRobot
Returns true if this is a multi axis robot (more than six active joints)
Declaration
public bool MultiAxisRobot { get; }
Property Value
Type | Description |
---|---|
Boolean | True if multi axis robot. |
NumActiveJoints
Gets the number of active joints, i.e. joints that are not dependant on other joints. This equals the number of values in the array when getting or setting joint values.
Declaration
public int NumActiveJoints { get; }
Property Value
Type | Description |
---|---|
Int32 |
Task
Gets the associated RsTask.
Declaration
public RsTask Task { get; }
Property Value
Type | Description |
---|---|
RsTask |
TraceColor
Gets or sets the color used to trace the TCP during simulation.
Declaration
public Color? TraceColor { get; set; }
Property Value
Type | Description |
---|---|
Nullable<Color> |
Remarks
This value is not persisted. If null, the color specified by the user in the TCP Trace dialog is used.
TraceTCP
Enables or disables a graphical trace of the active TCP during simulation.
Declaration
public bool TraceTCP { get; set; }
Property Value
Type | Description |
---|---|
Boolean |
Remarks
Only valid for TCP robots.
UsesCfx
Returns true if the Cfx parameter is used by this robot model, otherwise false. The performance of GetAllConfigurations is better for robots that does not use Cfx since the number of possible configurations are smaller.
Declaration
public bool UsesCfx { get; }
Property Value
Type | Description |
---|---|
Boolean | True if Cfx is used, otherwise false. |
Methods
AfterLoad(PimDocument)
Declaration
protected override void AfterLoad(PimDocument doc)
Parameters
Type | Name | Description |
---|---|---|
RobotStudio.API.Persistence.PimDocument | doc |
Overrides
AttachToFlange(IAttachableChild, Boolean)
Attaches the specified IAttachableChild to the flange of the Mechanism. The Mechansim must have exactly one flange.
Declaration
public bool AttachToFlange(IAttachableChild child, bool mount)
Parameters
Type | Name | Description |
---|---|---|
IAttachableChild | child | The IAttachableChild to attach to the link of this flange. |
Boolean | mount | Specifies if the position of the child shall be affected by the attachment or not. See Attachment for details. |
Returns
Type | Description |
---|---|
Boolean | True on success. |
AttachToFlange(IAttachableChild, Boolean, Matrix4)
Attaches the specified IAttachableChild to the first flange of the Mechanism.
Declaration
public bool AttachToFlange(IAttachableChild child, bool mount, Matrix4 offset)
Parameters
Type | Name | Description |
---|---|---|
IAttachableChild | child | The IAttachableChild to attach to the link of this flange. |
Boolean | mount | Specifies if the position of the child shall be affected by the attachment or not. See Attachment for details. |
Matrix4 | offset | Specifies the offset from the parent to the child. |
Returns
Type | Description |
---|---|
Boolean | True on success. |
CalculateForwardKinematics(Double[], out ForwardKinematicsResult)
Calculates forward kinematics for the mechanism. Given the specified mechanism joint values, the resulting TCP (tool0) transform is returned.
Declaration
public Matrix4 CalculateForwardKinematics(double[] jointValues, out ForwardKinematicsResult insideLimits)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues | Array of mechanism joint values, for which to calculate forward kinematics. |
ForwardKinematicsResult | insideLimits | Out parameter that specifies if the forward kinematics calculation failed or succeded. |
Returns
Type | Description |
---|---|
Matrix4 | The transform of the TCP (tool0) if the mechanism were positioned according to the specified joint values. |
Remarks
This method is thread-safe as long as no other RobotStudio API calls are made concurrently that may change the model. Exception: Mechanisms with closed kinematic loops such as the IRB360.
CalculateInverseKinematics(Matrix4, Matrix4, Boolean, out Double[])
Declaration
olete("Use CalculateInverseKinematicsAsync() instead")]
public bool CalculateInverseKinematics(Matrix4 pose, Matrix4 toolMat, bool fixedObject, out double[] resultJointVector)
Parameters
Type | Name | Description |
---|---|---|
Matrix4 | pose | |
Matrix4 | toolMat | |
Boolean | fixedObject | |
Double[] | resultJointVector |
Returns
Type | Description |
---|---|
Boolean |
CalculateInverseKinematics(Matrix4, Double[], Double[], Matrix4, Boolean, out Double[])
Calculate inverse kinematics given a pose and a starting set of joint values.
Declaration
public bool CalculateInverseKinematics(Matrix4 pose, double[] referenceJointValues, double[] integratedUnitsJointValues, Matrix4 toolMat, bool fixedObject, out double[] resultJointVector)
Parameters
Type | Name | Description |
---|---|---|
Matrix4 | pose | |
Double[] | referenceJointValues | |
Double[] | integratedUnitsJointValues | |
Matrix4 | toolMat | |
Boolean | fixedObject | |
Double[] | resultJointVector | Out parameter containing the result. |
Returns
Type | Description |
---|---|
Boolean | True on success. |
CalculateInverseKinematics(RsRobTarget, RsWorkObject, RsToolData, Int32[], out Double[])
Calculates inverse kinematics for the mechanism given a RsTarget, RsWorkObject and RsToolData.
Declaration
public bool CalculateInverseKinematics(RsRobTarget robTarget, RsWorkObject workObject, RsToolData tool, int[] cfg, out double[] resultJointVector)
Parameters
Type | Name | Description |
---|---|---|
RsRobTarget | robTarget | |
RsWorkObject | workObject | |
RsToolData | tool | |
Int32[] | cfg | |
Double[] | resultJointVector | Out parameter that contains the joint values, the mechanism would have if it was moved to the target position. If this method returns false, the joint values are undefined. |
Returns
Type | Description |
---|---|
Boolean | True, if the mechanism can move to the target position, otherwise false. |
CalculateInverseKinematics(RsTarget, RsToolData, Boolean, out Double[])
Calculates inverse kinematics for the mechanism. Given the specified RsTarget and RsToolData, this method returns the joint values the mechanism would have if it was moved to the pose. A mechanism can often reach the specified pose with different arm configurations. Using the useConfiguration you force the arm configuration stored in the RsTarget to be used.
Declaration
public bool CalculateInverseKinematics(RsTarget target, RsToolData tool, bool useConfiguration, out double[] resultJointVector)
Parameters
Type | Name | Description |
---|---|---|
RsTarget | target | The target position. This is the position that shall coincide with the tool. |
RsToolData | tool | The tool that should coincide with the target. The RobotHold property is used to determince if the tool is stationary or held by the robot. |
Boolean | useConfiguration | Specifies if the exact arm configuration stored in the target shall be used for the calculation. If set to true, the arm configuration is used. In this case this method returns true only if the mechanism can move to the specified target with its specified arm configuration. If the parameter is set to false, the arm configuration that is closes to the current mechanism joint values is returned, if the target is reachable. |
Double[] | resultJointVector | Out parameter that contains the joint values, the mechanism would have if it was moved to the target position. If this method returns false, the joint values are undefined. |
Returns
Type | Description |
---|---|
Boolean | True, if the mechanism can move to the target position, otherwise false. |
Remarks
When using this overload the target position shall not be converted to to mechanism base frame coordinates.
CalculateInverseKinematicsAsync(Matrix4, Matrix4, Boolean)
Calculate inverse kinematics from a pose.
Declaration
public Task<double[]> CalculateInverseKinematicsAsync(Matrix4 pose, Matrix4 toolMat, bool fixedObject)
Parameters
Type | Name | Description |
---|---|---|
Matrix4 | pose | |
Matrix4 | toolMat | |
Boolean | fixedObject |
Returns
Type | Description |
---|---|
Task<Double[]> |
CalculateInverseKinematicsAsync(Matrix4, Double[], Double[], Matrix4, Boolean)
Calculate inverse kinematics given a pose and a starting set of joint values.
Declaration
public Task<double[]> CalculateInverseKinematicsAsync(Matrix4 pose, double[] referenceJointValues, double[] integratedUnitsJointValues, Matrix4 toolMat, bool fixedObject)
Parameters
Type | Name | Description |
---|---|---|
Matrix4 | pose | |
Double[] | referenceJointValues | |
Double[] | integratedUnitsJointValues | |
Matrix4 | toolMat | |
Boolean | fixedObject |
Returns
Type | Description |
---|---|
Task<Double[]> |
CalculateInverseKinematicsAsync(RsRobTarget, RsWorkObject, RsToolData, Int32[])
Calculates inverse kinematics for the mechanism given a RsTarget, RsWorkObject and RsToolData.
Declaration
public Task<double[]> CalculateInverseKinematicsAsync(RsRobTarget robTarget, RsWorkObject workObject, RsToolData tool, int[] cfg)
Parameters
Type | Name | Description |
---|---|---|
RsRobTarget | robTarget | |
RsWorkObject | workObject | |
RsToolData | tool | |
Int32[] | cfg |
Returns
Type | Description |
---|---|
Task<Double[]> | Joint values if the mechanism can move to the target position, otherwise null. |
CalculateInverseKinematicsAsync(RsTarget, RsToolData, Boolean)
Calculates inverse kinematics for the mechanism. Given the specified RsTarget and RsToolData, this method returns the joint values the mechanism would have if it was moved to the pose. A mechanism can often reach the specified pose with different arm configurations. Using the useConfiguration you force the arm configuration stored in the RsTarget to be used.
Declaration
public Task<double[]> CalculateInverseKinematicsAsync(RsTarget target, RsToolData tool, bool useConfiguration)
Parameters
Type | Name | Description |
---|---|---|
RsTarget | target | The target position. This is the position that shall coincide with the tool. |
RsToolData | tool | The tool that should coincide with the target. The RobotHold property is used to determince if the tool is stationary or held by the robot. |
Boolean | useConfiguration | Specifies if the exact arm configuration stored in the target shall be used for the calculation. If set to true, the arm configuration is used. In this case this method returns true only if the mechanism can move to the specified target with its specified arm configuration. If the parameter is set to false, the arm configuration that is closes to the current mechanism joint values is returned, if the target is reachable. |
Returns
Type | Description |
---|---|
Task<Double[]> | Joint values if the mechanism can move to the target position, otherwise null. |
Remarks
When using this overload the target position shall not be converted to to mechanism base frame coordinates.
CanReach(Matrix4, Matrix4)
Declaration
olete("Use CanReachAsync() instead")]
public bool CanReach(Matrix4 pose, Matrix4 toolMat)
Parameters
Type | Name | Description |
---|---|---|
Matrix4 | pose | |
Matrix4 | toolMat |
Returns
Type | Description |
---|---|
Boolean |
CanReach(RsRobTarget, RsWorkObject, RsToolData)
Declaration
olete("Use CanReachAsync() instead")]
public bool CanReach(RsRobTarget robTarget, RsWorkObject workObject, RsToolData tool)
Parameters
Type | Name | Description |
---|---|---|
RsRobTarget | robTarget | |
RsWorkObject | workObject | |
RsToolData | tool |
Returns
Type | Description |
---|---|
Boolean |
CanReachAsync(Matrix4, Matrix4)
Checks if the specified target position can be reached with the specified tool. A mechanism can often reach the specified target with different arm configurations. This method returns true as long as there is at least one arm configuration with which the robot can reach the target.
Declaration
public Task<bool> CanReachAsync(Matrix4 pose, Matrix4 toolMat)
Parameters
Type | Name | Description |
---|---|---|
Matrix4 | pose | The target position. This is the position that shall coincide with the tool. |
Matrix4 | toolMat | The tool frame that should coincide with the target. |
Returns
Type | Description |
---|---|
Task<Boolean> | True, if the mechanism can move to the target position, otherwise false. |
CanReachAsync(RsRobTarget, RsWorkObject, RsToolData)
Checks if the specified target position can be reached with the specified tool. A mechanism can often reach the specified target with different arm configurations. This method returns true as long as there is at least one arm configuration with which the robot can reach the target.
Declaration
public Task<bool> CanReachAsync(RsRobTarget robTarget, RsWorkObject workObject, RsToolData tool)
Parameters
Type | Name | Description |
---|---|---|
RsRobTarget | robTarget | The target position. This is the position that shall coincide with the tool. |
RsWorkObject | workObject | The workobject to use. |
RsToolData | tool | The tool that should coincide with the target. The RobotHold property is used to determine if the tool is stationary or held by the robot. |
Returns
Type | Description |
---|---|
Task<Boolean> | True, if the mechanism can move to the target position, otherwise false. |
ClearTrace()
Removes the graphical trace of the TCP.
Declaration
public void ClearTrace()
CreateFromScript(String)
Declaration
olete("No longer supported")]
public static Mechanism CreateFromScript(string fileName)
Parameters
Type | Name | Description |
---|---|---|
String | fileName |
Returns
Type | Description |
---|---|
Mechanism |
CreateFromScriptAsync(String)
This method is for internal use only.
Declaration
public static Task<Mechanism> CreateFromScriptAsync(string fileName)
Parameters
Type | Name | Description |
---|---|---|
String | fileName |
Returns
Type | Description |
---|---|
Task<Mechanism> |
GetActiveJoints()
This method returns the (1-based) indices of the joints used by this mechanism, as an array of integers. The length of the array depends on how many joints are used. Some mechanism models have less than six axis. The indices can be used together with the result from GetJointValues()
Declaration
public int[] GetActiveJoints()
Returns
Type | Description |
---|---|
Int32[] | An array containing the indices of each joint that is used by this mechanism. |
Exceptions
Type | Condition |
---|---|
ArgumentException | |
ArgumentNullException |
See Also
GetAllConfigurations(RsMoveInstruction)
Declaration
olete("Use GetAllConfigurationsAsync() instead")]
public ConfigurationData[] GetAllConfigurations(RsMoveInstruction moveInstruction)
Parameters
Type | Name | Description |
---|---|---|
RsMoveInstruction | moveInstruction |
Returns
Type | Description |
---|---|
ConfigurationData[] |
GetAllConfigurations(RsMoveInstruction, Boolean)
Declaration
olete("Use GetAllConfigurationsAsync() instead")]
public ConfigurationData[] GetAllConfigurations(RsMoveInstruction moveInstruction, bool includeTurns)
Parameters
Type | Name | Description |
---|---|---|
RsMoveInstruction | moveInstruction | |
Boolean | includeTurns |
Returns
Type | Description |
---|---|
ConfigurationData[] |
GetAllConfigurations(RsTarget, RsToolData)
Returns reachable arm configurations for the specified target.
Declaration
olete("Use GetAllConfigurationsAsync() instead")]
public ConfigurationData[] GetAllConfigurations(RsTarget target, RsToolData tool)
Parameters
Type | Name | Description |
---|---|---|
RsTarget | target | The target for which to find reachable configurations. |
RsToolData | tool | The tool that should coincide with the target. The RobotHold property is used to determince if the tool is stationary or held by the robot. |
Returns
Type | Description |
---|---|
ConfigurationData[] | An array of ConfigurationData with which the mechanism can reach the specified target. |
GetAllConfigurations(RsTarget, RsToolData, Boolean)
Declaration
olete("Use GetAllConfigurationsAsync() instead")]
public ConfigurationData[] GetAllConfigurations(RsTarget target, RsToolData tool, bool includeTurns)
Parameters
Type | Name | Description |
---|---|---|
RsTarget | target | |
RsToolData | tool | |
Boolean | includeTurns |
Returns
Type | Description |
---|---|
ConfigurationData[] |
GetAllConfigurations(RsTarget, RsToolData, Int32[])
Declaration
olete("Use GetAllConfigurationsAsync() instead")]
public ConfigurationData[] GetAllConfigurations(RsTarget target, RsToolData tool, int[] cfxFilter)
Parameters
Type | Name | Description |
---|---|---|
RsTarget | target | |
RsToolData | tool | |
Int32[] | cfxFilter |
Returns
Type | Description |
---|---|
ConfigurationData[] |
GetAllConfigurations(RsTarget, RsToolData, Int32[], Boolean)
Declaration
olete("Use GetAllConfigurationsAsync() instead")]
public ConfigurationData[] GetAllConfigurations(RsTarget target, RsToolData tool, int[] cfxFilter, bool includeTurns)
Parameters
Type | Name | Description |
---|---|---|
RsTarget | target | |
RsToolData | tool | |
Int32[] | cfxFilter | |
Boolean | includeTurns |
Returns
Type | Description |
---|---|
ConfigurationData[] |
GetAllConfigurations(Boolean)
Declaration
olete("Use GetAllConfigurationsAsync() instead")]
public ConfigurationData[] GetAllConfigurations(bool includeTurns)
Parameters
Type | Name | Description |
---|---|---|
Boolean | includeTurns |
Returns
Type | Description |
---|---|
ConfigurationData[] |
GetAllConfigurationsAsync(RsMoveInstruction, Boolean)
Returns reachable arm configurations for the specified move instruction.
Declaration
public Task<ConfigurationData[]> GetAllConfigurationsAsync(RsMoveInstruction moveInstruction, bool includeTurns)
Parameters
Type | Name | Description |
---|---|---|
RsMoveInstruction | moveInstruction | The move instruction for which to find reachable configurations. The target, tool and workobject specified in the instruction is used. |
Boolean | includeTurns | Only the base configurations will be returned if this parameter is set to false. If true, the turns of the base configurations will be added. |
Returns
Type | Description |
---|---|
Task<ConfigurationData[]> | An array of ConfigurationData with which the mechanism can reach the specified target. |
GetAllConfigurationsAsync(RsTarget, RsToolData, Boolean)
Returns reachable arm configurations for the specified target.
Declaration
public Task<ConfigurationData[]> GetAllConfigurationsAsync(RsTarget target, RsToolData tool, bool includeTurns)
Parameters
Type | Name | Description |
---|---|---|
RsTarget | target | The target for which to find reachable arm configurations. |
RsToolData | tool | The tool that should coincide with the target. The RobotHold property is used to determince if the tool is stationary or held by the robot. |
Boolean | includeTurns | Only the base configurations will be returned if this parameter is set to false. If true, the turns of the base configurations will be added. |
Returns
Type | Description |
---|---|
Task<ConfigurationData[]> | An array of ConfigurationData with which the mechanism can reach the specified target. |
GetAllConfigurationsAsync(RsTarget, RsToolData, Int32[], Boolean)
Returns reachable arm configurations for the specified target.
Declaration
public Task<ConfigurationData[]> GetAllConfigurationsAsync(RsTarget target, RsToolData tool, int[] cfxFilter, bool includeTurns)
Parameters
Type | Name | Description |
---|---|---|
RsTarget | target | The target for which to find reachable configurations. |
RsToolData | tool | The tool that should coincide with the target. The RobotHold property is used to determince if the tool is stationary or held by the robot. |
Int32[] | cfxFilter | An array of integers which specifies Cfx values to be included in the resulting array. This parameter is only applicable for a bending bacwards robot. Cfx values which are not specified in the filter will not be considered, which will improve performance. Often you know that you are only interested in configurations where, for example, the wrist is in front of axis 1. , forRobotHold property is used to determince if the tool is stationary or held by the robot. |
Boolean | includeTurns | Only the base configurations will be returned if this parameter is set to false. If true, the turns of the base configurations will be added. |
Returns
Type | Description |
---|---|
Task<ConfigurationData[]> | An array of ConfigurationData with which the mechanism can reach the specified target. |
GetAllConfigurationsAsync(Boolean)
Returns reachable arm configurations for the current pose.
Declaration
public Task<ConfigurationData[]> GetAllConfigurationsAsync(bool includeTurns)
Parameters
Type | Name | Description |
---|---|---|
Boolean | includeTurns |
Returns
Type | Description |
---|---|
Task<ConfigurationData[]> |
GetCalibrationPosition(Int32)
Returns the calibration transform for a joint.
Declaration
public Matrix4 GetCalibrationPosition(int jointIndex)
Parameters
Type | Name | Description |
---|---|---|
Int32 | jointIndex |
Returns
Type | Description |
---|---|
Matrix4 | Calibration transform (relative to model zero position) |
GetConfiguration()
Returns the current configuration.
Declaration
public ConfigurationData GetConfiguration()
Returns
Type | Description |
---|---|
ConfigurationData |
GetConfiguration(Double[])
Returns the configuration that corresponds to the given joint values.
Declaration
public ConfigurationData GetConfiguration(double[] jointValues)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues |
Returns
Type | Description |
---|---|
ConfigurationData |
GetConfigurationAsync()
Returns the current configuration.
Declaration
public Task<ConfigurationData> GetConfigurationAsync()
Returns
Type | Description |
---|---|
Task<ConfigurationData> |
GetConfigurationAsync(Double[])
Returns the configuration that corresponds to the given joint values.
Declaration
public Task<ConfigurationData> GetConfigurationAsync(double[] jointValues)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues |
Returns
Type | Description |
---|---|
Task<ConfigurationData> |
GetDenavitHartenbergParameters()
Gets the DenavitHartenbergParameters for all joints.
Declaration
public DenavitHartenbergParameters[] GetDenavitHartenbergParameters()
Returns
Type | Description |
---|---|
DenavitHartenbergParameters[] | An array with all DenavitHartenbergParameters or null when none are available. |
Remarks
Denavit and Hartenberg parameters are only available for serial manipulators. The FlexPicker is an example of a cloosed loop manipulator for which the kinematics cannot be described using Denavit and Hartenberg parameters.
See Also
GetFlange(Int32)
Get a Flange to which other entities can be attached.
Declaration
public Flange GetFlange(int index)
Parameters
Type | Name | Description |
---|---|---|
Int32 | index | The index of the flange to be retrieved. |
Returns
Type | Description |
---|---|
Flange | A Flange |
GetFlanges()
Declaration
public Flange[] GetFlanges()
Returns
Type | Description |
---|---|
Flange[] |
GetHomePosition()
Returns the defined home position in form of a collection of values. The number of values vary depending on the number of joints in the mechanism.
Declaration
public double[] GetHomePosition()
Returns
Type | Description |
---|---|
Double[] | An array of home position for each joint. |
GetJointLimits(Double[], out Double[], out Double[])
Get joint limits given a set of joint values.
Declaration
public void GetJointLimits(double[] jointValues, out double[] minLimits, out double[] maxLimits)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues | Joint values to use when evaluating limits. Must have length equal to NumActiveJoints |
Double[] | minLimits | Out parameter giving the minimum limits. |
Double[] | maxLimits | Out parameter giving the maximum limits. |
GetJointLimits(out Double[], out Double[])
Get joint limits.
Declaration
public void GetJointLimits(out double[] minLimits, out double[] maxLimits)
Parameters
Type | Name | Description |
---|---|---|
Double[] | minLimits | Out parameter giving the minimum limits. |
Double[] | maxLimits | Out parameter giving the maximum limits. |
GetJointTransform(Int32)
Get the transform for a joint using the current joint values
The index of the joint for which the transform shall be retrieved. Must be a value between 0 and ABB.Robotics.RobotStudio.Declaration
public Matrix4 GetJointTransform(int jointIndex)
Parameters
Type | Name | Description |
---|---|---|
Int32 | jointIndex |
Returns
Type | Description |
---|---|
Matrix4 |
GetJointTransform(Int32, Double[], out Matrix4)
Get the transform for a joint using specified joint values
The index of the joint for which the transform shall be retrieved. Must be a value between 0 and ABB.Robotics.RobotStudio.Declaration
public bool GetJointTransform(int jointIndex, double[] jointValues, out Matrix4 jointTransform)
Parameters
Type | Name | Description |
---|---|---|
Int32 | jointIndex | |
Double[] | jointValues | |
Matrix4 | jointTransform |
Returns
Type | Description |
---|---|
Boolean |
GetJointTypes()
Get an array containing the type for each contained joint. For a mechanism with ABB.Robotics.RobotStudio.
Declaration
public JointType[] GetJointTypes()
Returns
Type | Description |
---|---|
JointType[] | An array with length 0 or an array with length equal to NumActiveJoints |
GetJointValues()
Returns the current joint values.
Declaration
public double[] GetJointValues()
Returns
Type | Description |
---|---|
Double[] |
GetParentJoint(GraphicComponent, out Int32)
Returns the joint index of a link, or -1.
Declaration
public bool GetParentJoint(GraphicComponent link, out int jointIndex)
Parameters
Type | Name | Description |
---|---|---|
GraphicComponent | link | The link. |
Int32 | jointIndex | Zero-based joint index. |
Returns
Type | Description |
---|---|
Boolean |
GetParentLink(Int32, out GraphicComponent)
Returns the parent link of a joint.
Declaration
public bool GetParentLink(int jointIndex, out GraphicComponent link)
Parameters
Type | Name | Description |
---|---|---|
Int32 | jointIndex | Zero-based joint index. Must be less than ABB.Robotics.RobotStudio. |
GraphicComponent | link |
Returns
Type | Description |
---|---|
Boolean |
GetStaticJointLimits(out Double[], out Double[])
Get static joint limits.
Declaration
public void GetStaticJointLimits(out double[] minLimits, out double[] maxLimits)
Parameters
Type | Name | Description |
---|---|---|
Double[] | minLimits | Out parameter giving the minimum limits. |
Double[] | maxLimits | Out parameter giving the maximum limits. |
GetSyncPosition()
Returns the defined sync position in form of a collection of values. The number of values are 0-6 depending on the number of joints used for corresponding mechanism.
Declaration
public double[] GetSyncPosition()
Returns
Type | Description |
---|---|
Double[] | An array of sync position for each joint. |
GetToolDataInfo()
Returns the tool datas for a mechanism that is a tool.
Declaration
public ToolDataInfo[] GetToolDataInfo()
Returns
Type | Description |
---|---|
ToolDataInfo[] |
GetTransitionTimes()
Gets transition times.
Declaration
public Dictionary<string[], double> GetTransitionTimes()
Returns
Type | Description |
---|---|
Dictionary<String[], Double> | A dictionary mapping pairs of position names to transition times. |
GetUserDefinedJointPositions()
Get user defined joint positions.
Declaration
public Dictionary<string, double[]> GetUserDefinedJointPositions()
Returns
Type | Description |
---|---|
Dictionary<String, Double[]> | A dictionary containing user defined joint positions. |
InsideLimits(Double[])
Evaluates if a set of joint values are inside the joint limits.
Declaration
public bool InsideLimits(double[] jointValues)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues | Joint values, must have length equal to NumActiveJoints |
Returns
Type | Description |
---|---|
Boolean | Returns true if inside joint limits. |
MoveToPose(String)
Moves the mechanism to a named pose.
Declaration
public bool MoveToPose(string jointPosition)
Parameters
Type | Name | Description |
---|---|---|
String | jointPosition | The name of the pose. |
Returns
Type | Description |
---|---|
Boolean | True if successful. |
SetActiveJoints(Int32[])
This method sets the indices of the joints used by this mechanism, as an array of integers. The length of the array depends on how many joints are used. Some mechanism models has less than six axis.
Declaration
public void SetActiveJoints(int[] jointMask)
Parameters
Type | Name | Description |
---|---|---|
Int32[] | jointMask | The indices of the joints used by this mechanism. |
Exceptions
Type | Condition |
---|---|
ArgumentException | |
ArgumentNullException |
See Also
SetHomePosition(Double[])
Declaration
public void SetHomePosition(double[] jointValues)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues |
SetJointLimits(Int32, Double, Double)
Sets the joint limits for a joint.
Declaration
public bool SetJointLimits(int jointIndex, double minLimit, double maxLimit)
Parameters
Type | Name | Description |
---|---|---|
Int32 | jointIndex | The index of the joint. |
Double | minLimit | The minimum limit. |
Double | maxLimit | The maximum limit. |
Returns
Type | Description |
---|---|
Boolean |
SetJointModelOffset(Int32, Double)
Sets an offset between the joint value and the nominal kinematic model for a joint. This can be used to modify the zero position of the mechanism.
Declaration
public void SetJointModelOffset(int jointIndex, double jointOffset)
Parameters
Type | Name | Description |
---|---|---|
Int32 | jointIndex | |
Double | jointOffset |
Remarks
This will only affect forward kinematics. Inverse kinematics uses the virtual controller which is assumed to take the offset into account internally. Joint limits are assumed to be adjusted accordingly by using SetJointLimits(Int32, Double, Double).
SetJointValues(Double[], Boolean)
Sets the mechanism joint values and updates joint values in the VC.
Declaration
public bool SetJointValues(double[] jointValues, bool updateController)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues | |
Boolean | updateController |
Returns
Type | Description |
---|---|
Boolean | True if the joint values are valid. |
SetJointValues(Double[], Boolean, Boolean)
ABB Internal use
Declaration
public bool SetJointValues(double[] jointValues, bool updateController, bool notify)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues | |
Boolean | updateController | |
Boolean | notify |
Returns
Type | Description |
---|---|
Boolean |
SetJointValues(Double[], Boolean, Double)
ABB Internal use
Declaration
olete("No longer supported")]
public bool SetJointValues(double[] jointValues, bool updateController, double timeStamp)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues | |
Boolean | updateController | |
Double | timeStamp |
Returns
Type | Description |
---|---|
Boolean |
SetJointValuesAsync(Double[], Boolean)
Sets the mechanism joint values and asynchronously updates joint values in the VC.
Declaration
public Task<bool> SetJointValuesAsync(double[] jointValues, bool updateController)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues | |
Boolean | updateController |
Returns
Type | Description |
---|---|
Task<Boolean> | True if the joint values are valid. |
SetJointValuesInternal(Double[], Double, Boolean)
ABB Internal use
Declaration
public bool SetJointValuesInternal(double[] jointValues, double timeStamp, bool notify)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues | |
Double | timeStamp | |
Boolean | notify |
Returns
Type | Description |
---|---|
Boolean |
SetSyncPosition(Double[])
Sets the defined sync position in form of a collection of values. The number of values are 0-6 depending on the number of joints used for corresponding mechanism.
Declaration
public void SetSyncPosition(double[] jointValues)
Parameters
Type | Name | Description |
---|---|---|
Double[] | jointValues |
SetTransitionTimes(Dictionary<String[], Double>)
Sets transition times.
Declaration
public void SetTransitionTimes(Dictionary<string[], double> value)
Parameters
Type | Name | Description |
---|---|---|
Dictionary<String[], Double> | value | A dictionary mapping pairs of position names to transition times. |
SetUserDefinedJointPositions(Dictionary<String, Double[]>)
Sets user defined joint positions.
Declaration
public void SetUserDefinedJointPositions(Dictionary<string, double[]> value)
Parameters
Type | Name | Description |
---|---|---|
Dictionary<String, Double[]> | value | A dictionary containing user defined joint positions. Each array should have the same length as NumActiveJoints |
Events
AnyJointValuesChanged
Declaration
public static event EventHandler AnyJointValuesChanged
Event Type
Type | Description |
---|---|
EventHandler |
JointValuesChanged
Declaration
public event EventHandler JointValuesChanged
Event Type
Type | Description |
---|---|
EventHandler |
TargetReachEvent
Declaration
olete("No longer supported")]
public event EventHandler TargetReachEvent
Event Type
Type | Description |
---|---|
EventHandler |