Kin_Pos_RRR_ReadConfig (FB) ¶ FUNCTION_BLOCK Kin_Pos_RRR_ReadConfig Allows to write the configuration of Kin_Pos_RRR. InOut: Scope Name Type Comment Input Config ConfigData The configuration data Output ArmState Kin_Pos_RRR_Arm_State ElbowState Kin_Pos_RRR_Elbow_State
Kin_Pos_RRR (FB) ¶ FUNCTION_BLOCK Kin_Pos_RRR IMPLEMENTS ISMPositionKinematicsInternal, ISMPositionKinematics_Offset2 , ISMKinematicWithConfigurations , ISMKinematicWithInfo2 Transformation FB for a 3 axis articulated robot consisting of three rotary joints. The first joint rotates around the z-axis, the second and third are parallel and rotate around the y-axis. This kinematics forms the first half of the 6-axis articulated robot. Machine coordinate system (MCS) Origin The intersection of axis 0 and the bottom of the robot. X Points “forward” toward the flange. Y Defined by X and Z so that the MCS becomes right-handed. Z Points upward. The machine coordinate system is shown at the bottom of axis 0. The sense of rotation is indicated by black arrows. The arrows point along the axis. The positive sense of rotation is given by the right-hand rule. For example, when axis 0 is turned in positive direction, the robot rotates counterclockwise when viewed from above. The location of the tool coordinate system (TCS) relative to the MCS in zero position: Tool coordinate system (TCS) Origin Relative to MCS: dX = a1 + d4 dY = -d3 dZ = d1 + a2 + a3 X Along the Z-Axis of the MCS in positive direction Y Along the Y-Axis of the MCS in negative direction Z Along the X-Axis of the MCS in positive direction The left figure shows the reference position of the kinematic, i.e. the position when all axes are in their zero-position. The names and signs of the parameters are due to the Denavit-Hartenberg convention. Robots with the following Denavit-Hartenberg configuration are supported (the values of d_i and a_i are supplied in the configuration): joint number joint offset link offset d_i link length a_i link twist 0 0° d1 a1 90° 1 90° 0 a2 0° 2 0° d3 a3 90° flange 0° d4 0 0° The single axes values have the following interpretation: a0 position of the first rotary axis in degrees a1 position of the second rotary axis in degrees a2 position of the third rotary axis in degrees The zero position of the kinematics can be adjusted by defining constant offsets for the axes. See inputs dOffsetA0 , dOffsetA1 and dOffsetA2 . Changing the offsets affects the location and orientation of the TCS. Note If this kinematics is used without an orientation-kinematics, then it is not compatible with tools (see SMC_GroupSetTool) that have a position offset. Attributes: sm_kin_libdoc InOut: Scope Name Type Comment Input d1 LREAL Denavit-Hartenberg Parameter d1, >= 0 a1 LREAL Denavit-Hartenberg Parameter a1, >= 0 a2 LREAL Denavit-Hartenberg Parameter a2, > 0 d3 LREAL Denavit-Hartenberg Parameter d3 a3 LREAL Denavit-Hartenberg Parameter a3, >= 0 d4 LREAL Denavit-Hartenberg Parameter d4, >= 0 dOffsetA0 LREAL Additional offset of axis A0. This offset is subtracted before the forward transformation and added after the inverse transformation. dOffsetA1 LREAL Additional offset of axis A1. This offset is subtracted before the forward transformation and added after the inverse transformation. dOffsetA2 LREAL Additional offset of axis A2. This offset is subtracted before the forward transformation and added after the inverse transformation. Properties: NumAxes Methods: AxesToCartesian AxesToCartesian_Offset AxesToConfiguration_Offset AxesToOrientation CartesianToAxes CartesianToAxes_Offset GetAxisProperties GetConfigurationDataSize GetDefaultConfigurationData GetKinematicsName GetOrientationImage IsSingularity ProjectPosition Structure: AxesToCartesian (Method) AxesToCartesian_Offset (Method) AxesToConfiguration_Offset (Method) AxesToOrientation (Method) CartesianToAxes (Method) CartesianToAxes_Offset (Method) GetAxisProperties (Method) GetConfigurationDataSize (Method) GetDefaultConfigurationData (Method) GetKinematicsName (Method) GetOrientationImage (Method) IsSingularity (Method) NumAxes (Property) ProjectPosition (Method)
Kin_Pos_RRR.AxesToCartesian (METH) ¶ METHOD AxesToCartesian : SMC_Error InOut: Scope Name Type Return AxesToCartesian SMC_Error Inout f SMC_Frame cd CONFIGDATA Inout Const a AXISPOS_REF
Kin_Pos_RRR.AxesToCartesian_Offset (METH) ¶ METHOD AxesToCartesian_Offset : SMC_Error InOut: Scope Name Type Return AxesToCartesian_Offset SMC_Error Inout f SMC_Frame cd CONFIGDATA Inout Const a AXISPOS_REF vOffset_TCP SMC_Vector3D
Kin_Pos_RRR.NumAxes (PROP) ¶ PROPERTY NumAxes : UDINT
Kin_Pos_RRR.ProjectPosition (METH) ¶ METHOD ProjectPosition InOut: Scope Name Type Inout vOut SM3M.SMC_VECTOR3D Inout Const vIn SM3M.SMC_VECTOR3D
Configuration ¶ Kin_Scara2_Z_Config (FunctionBlock) Kin_Scara2_Z_ReadConfig (FunctionBlock)
Kin_Scara2_Z_Config (FB) ¶ FUNCTION_BLOCK Kin_Scara2_Z_Config This FB contains the data that defines the configuration of SM3_Trafo_Scara2_Z. InOut: Scope Name Type Comment Input xElbowRight BOOL TRUE: The angle of the second joint is greater than 0° and lesser than 180° FALSE: The angle of the second joint is lesser than 0° and greater than -180° nPeriodA1 DINT Determines the period used for axis A1. If the range of A1 is greater than 360°, the period to choose can be set here. If the value is zero, then the period is determined automatically, based on the last position. A positive value i > 0 means the range [360°*(i-1)-180° .. 360°*i-180°[ is used. A negative value i < 0 means the range [360°*i-180° .. 360°*(i+1)-180°[ is used. Note if nPeriodA1 <> 0 and the chosen period is not feasible due to the axis limits, an error is created during transformation (CartesianToAxes). nPeriodA2 DINT See nPeriodA1 . Output Config ConfigData The configuration data
Kin_Scara2_Z_ReadConfig (FB) ¶ FUNCTION_BLOCK Kin_Scara2_Z_ReadConfig This FB reads configuration data of SM3_Trafo_Scara2_Z. InOut: Scope Name Type Comment Input Config ConfigData The configuration data Output xElbowRight BOOL TRUE: looking from joint 0 to joint 2, the elbow (joint 1) is on the right side. The angle of joint 1 is greater than 0° and lesser than 180°. FALSE: looking from joint 0 to joint 2, the elbow (joint 1) is on the left side. The angle of joint 1 is lesser than 0° and greater than -180°. xElbowSingularity BOOL TRUE: looking from joint 0 to joint 2, the elbow (joint 1) is straight (singularity). The angle of joint 1 is very close to either 0°, 180° or 360° nPeriodA1 DINT Determines the period used for orientation axis A1. If the range of A1 is greater than 360°, the period to choose can be set here. If the value is zero, then the period is determined automatically, based on the last position. A positive value i > 0 means the range [360°*(i-1)-180° .. 360°*i-180°[ is used. A negative value i < 0 means the range [360°*i-180° .. 360°*(i+1)-180°[ is used. Note if nPeriodA2 <> 0 and the chosen period is not feasible due to the axis limits, an error is created during transformation (CartesianToAxes). nPeriodA2 DINT See nPeriodA1 .
Kin_Polar (FB) ¶ FUNCTION_BLOCK Kin_Polar IMPLEMENTS ISMPositionKinematicsInternal, ISMKinematicWithInfo2 Transformation FB for polar kinematics. A Polar Systems consists of one distance and one direction axis. Machine coordinate system (MCS) Origin Location of the TCP when the position value of the linear axis (a1) is 0. X The X axis is defined so that a positive velocity of the linear axis (a1) while the rotary axis (a0) is at 0° leads to a movement purely along the X axis in positive direction. Y The Y axis is defined so that a positive velocity of the linear axis (a1) while the rotary axis (a0) is at 90° leads to a movement purely along the Y axis in positive direction. The location of the tool coordinate system (TCS) relative to the MCS in zero position: Tool coordinate system (TCS) Origin Relative to MCS: dX = 0 dY = 0 dZ = 0 X Along the X-Axis of the MCS in positive direction Y Along the Y-Axis of the MCS in positive direction Z Along the Z-Axis of the MCS in positive direction The single axes values have the following interpretation: a0 position of the rotary axis around Z in degrees. referred to as ‘C’ in the section ‘mapping to axes’ . a1 position of the linear axis in the direction of X axis (>= 0). referred to as ‘R’ in the section ‘mapping to axes’. Note This position kinematics does not support orientation mode “Axis” for CP movements. If this kinematics is used without an orientation-kinematics, then it is not compatible with tools (see SMC_GroupSetTool) that have a position offset in a direction other than the Z direction. Attributes: sm_kin_libdoc Properties: NumAxes Methods: AxesToCartesian AxesToOrientation CartesianToAxes CartesianToAxes_Offset GetAxisProperties GetKinematicsName GetOrientationImage IsSingularity ProjectPosition Structure: AxesToCartesian (Method) AxesToOrientation (Method) CartesianToAxes (Method) CartesianToAxes_Offset (Method) GetAxisProperties (Method) GetKinematicsName (Method) GetOrientationImage (Method) IsSingularity (Method) NumAxes (Property) ProjectPosition (Method)