ID : 11169
CurLmt
Function
Enable/Disable and configure the current limiting function.
Syntax
CurLmt True/False, axis number,setting value
Guaranteed Entry
- True/False
- Enable/Disable the servo lock by an integer type data.
To enable this command, enter True or an integer other than 0.
To disable this command, enter False or 0. - Axis number
- Designate an axis number by Integer Type data. If the argument True/False is set to False, you can use "0" to specify all axes as target.
- Setting value
- Designate a current limit setting value by single precision real number type data. The unit is "%" assuming the rated current value is 100. You can specify a value from 0. In case of "False," no designation is needed.
Description
This is a command to configure True/False for the current limiting function.
To execute this command, the task must acquire target axis control.
Current limiting function will not be disabled, even if release of axis control or completion of a task. Enable it only if necessary.
For 6-Axis robot, the current limiting function can only be enabled when the gravity compensation control function is enabled.
Related Terms
Attention
- If you enable the current limiting function or change only the current limiting value while the function is enabled, these operations will be executed immediately regardless of the operating condition.
- Execution of this command during machine lock is ignored.
- Using the current limiting function while the axis is operating will cause an error.
- The deviation tolerance is not reset to the default value when the current limit is released.
- The gravity compensation control function is not available when the current limiting function is executed to an auxiliary axis.
In limiting the electric current, be sure to adjust the current limiting value starting from a larger value to prevent the robot arm from falling or performing unexpected operation due to an external force.
Enabling the function during high speed motion is dangerous. If you enable the current limiting while the robot operates with pass-motion in high speed, an overshooting may frequently occur. To avoid overshooting, enable the current limiting while the robot stops or moves with slow speed.
' Example of frequent overshooting
Move P, @p P[10], Speed = 100 'Pass motion
Curlmt True, 1, 20 'Current limiting function On
Curlmt True, 2, 20 'Current limiting function On
Note that setting a small value for the current limit may cause the robot arm or the auxiliary axis to fall or move in an unexpected direction due to their own weights or an external force applied by the equipment.
If the robot moves at high speed when the current limiting function is enabled, overshooting may occur, and the robot may exceed the motion range. Operate at low speed.
Before using the current limiting function, be sure to confirm if the target axis has stopped.
Using the function while the axis is operating may cause the axis to perform unexpected operation.
Example
'!TITLE "Setting of Current Limiting Function for 6-Axis robot"
' True/False of the current limiting function
Sub Sample_CurLmt
Dim aaa As Joint
Dim bbb As Joint
aaa = J( 0, 0, 0, 0, 0, 0 )
bbb = J( 90, 0, 0, 0, 0, 0 )
TakeArm Keep = 1
Motor True
' Set the external speed to 100
ExtSpeed 100
' Move from the current position to the aaa coordinate position
Move P, @E aaa
' Set position deviation tolerance to 52.27
ErAlw True, 1, 52.27
' Set dead gravity compensation control function to be enabled
GrvCtrl True
' Set current limiting function to 50%
CurLmt True, 1, 50
'Clear logs
ClearLog
'Start recording logs
StartLog
' Move from the current position to the bbb coordinate position
Move P, @E bbb
'Stop recording logs
StopLog
' Set current limiting function to be disabled
CurLmt False, 1
' Set dead gravity compensation control function to be disabled
GrvCtrl False
' Set position deviation tolerance to be disabled
ErAlw False, 1
End SubID : 11169

