<< Prev        Next >>

ID : 219

CurLmt

Function

Configure the current limiting function and True/False.

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.

For 4-Axis robot, enable the current limiting function under the condition that the gravity offsetting function is enabled.

Attention

  • When you set the current limiting function to disable, the target axis stops its motion first, and then the current limiting function is disabled. Even if the target axis has not reached the instruction value, when the target axis remains stop-state for a certain period of time, the axis is deemed as the stop-state and the current limiting function is disabled.
  • The following operations will start immediately, regardless of the motion status;
    : turning ON of the current limiting function,
    : changing the current limiting value while this function is ON.
  • Execution of this command during machine lock is ignored.
  • Unlike RC7 controller, the deviation tolerance value is not initialized when the current limit is cancelled.
  • In the compliance function without force sensor, the current limit value and the deviation tolerance value are temporarily rewritten during processing, and then these values are initialized when the limits are cancelled.
    To set the current limit value or the deviation tolerance value back to the values that have been set before the compliance function activation, set these values again.

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

Setting a small vale in the argument setting value will cause the arm to drop by its own weight. Please pay attention.

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.

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, @0 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 the servo logs
  Syslog.Servo.Clear 

  'Start recording servo logs
  Syslog.Servo.Start 

  ' Move from the current position to the bbb coordinate position
  Move P, @0 bbb

 'Stop recording servo logs 
  Syslog.Servo.Stop

  ' 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 Sub

ID : 219

<< Prev        Next >>