ST_SetCurLmt (Statement) [Version 1.9 or later]


Sets the limit of motor current to be applied to the specified axis.


ST_SetCurLmt <AxisNumber>, <Value>


Limits the value of motor current (torque) to be applied to the axis specified by <AxisNumber> to the value specified by <Value>. This command is useful when you want to limit torque that a workpiece will undergo during insertion or butting jobs.
The maximum value of <Value> is 100 which refers to the motor rating current.
If any value exceeding the allowable limit for each axis is specified, the value will be automatically limited to that allowable limit.
Set a value of 1 or above. If 0 or a negative number is set, Error "6003 Excess in effective value range" will result.



  • When the motor current is limited with ST_SetCurLmt, the robot cannot move at the maximum speed or acceleration. Use ST_SetCurLmt only at steps that need the current limit. When using ST_SetCurLmt, decrease the acceleration.
  • If a workpiece bumps against something at high speed even if the driving force is controlled by limiting the motor current, the impact is considerable due to the inertia of the workpiece, end-effector and axis. Set the current limit just before the workpiece comes into contact with the object and reduce the speed.
  • Set the current limit when the robot is on halt. If it is set during a pass motion, an error is likely to occur.
  • Execute this command in a TAKEARMed task that has obtained arm-semaphore. If this command is executed without arm-semaphore obtained, Error "21F7 Cannot take arm semaphore" will result.
  • If the current limit reset value in User Preferences is set to any value other than "1", "3", "5", or "7", the compensation value will be reset to "0" when you turn on the motor power.
    To make the current limit function effective immediately after switching on the motor power, set the current limit reset value to "1."
6-axis
  • When setting the current limit, be sure to enable the gravity compensation function. If the current limit is set when the gravity compensation function is disabled, Error "665A Cannot set current limit" will result. For the gravity compensation function, refer to ST_SetGravity.
  • Set the mass of payload and the payload center of gravity accurately.
    Otherwise, the robot may move down due to gravity if you set a low current limit value (e.g., less than 30). For the entry procedure of the mass of payload and the payload center of gravity, refer to the Programmer's Manual, "4.7 Control Set of Motion Optimization in User Preferences."
  • If the current limit reset value is set to "1," the robot might move down due to gravity the moment you turn on the motor power. Reset the current limit by executing ST_ResetCurLmt when the motor power is off and then switch on the motor power.
  • If you do not know the accurate mass of payload or its center of gravity or if the robot moves down in spite of accurate settings, then use the gravity offset function (ST_SetGrvOffset) that compensates for the gravity compensation value.
4-axis HS-E
When setting the current limit to the Z-axis or the T-axis of the 4-axis robot without an air balance mechanism, the Z-axis may move down or the T-axis may rotate if you set a low current limit value. Set current limit after execution the gravity compensation function (ST_SetZBalance) for the Z and the T-axis.


6-axis
ST_SetGravity
'Enable the gravity offset.
ST_SetGrvOffset
'Compensate the gravity offset value
ST_SetEralw 2, 20
'Set the allowable deviation of the 2nd axis to 20
'degrees
ST_SetCurLmt 2, 30
'Set the current limit of the 2nd axis to 30%

4-axis
ST_SetEralw 2, 20
'Set the allowable deviation of the 2nd axis to 20
'degrees
ST_SetCurLmt 2, 30
'Set the current limit of the 2nd axis to 30%

4-axis HS-E
ST_SetZBalance
'Set the gravity compensation value of the Z-axis
ST_SetEralw 3, 100
'Set the allowable deviation of the Z-axis to 100 mm
ST_SetEralw 4, 30
'Set the allowable deviation of the T-axis to 30
'degrees
ST_SetCurLmt 3, 10
'Set the current limit of the Z-axis to 10%
ST_SetCurLmt 4, 10
'Set the current limit of the T-axis to 10%


Top