Definition
set_damping_factor(damping_factor, time)
Features
In force control, This function sets the damping factor based on the global coordinate (refer to set_ref_coord())
Caution
In non-FTS models (A0509, A0912, A0509F, A0912F, E0509), compliance control is only possible in the translation direction, and the control error may be large.
Parameters
|
Parameter Name |
Data Type |
Default Value |
Description |
|---|---|---|---|
|
damping_factor |
float[6] |
[1.0, 1.0, 1.0, 1.0, 1.0, 1.0] |
(Translation x, y, z), (Rotation x, y, z) Range: 0.1 - 2.0 |
|
time |
float |
0 |
Damping factor varying time [sec] Range: 0 - 1.0 * Linear transition during the specified time |
Caution
In the Non-FTS A & E model, the data type of the damping_factorparameter can be either float[6] or float[3] (rotational parameter is automatically set to the default value)
Note
-
When the damping factor is set to the default value (1.0), it operates with the default damping value set according to the robot model.
-
When the damping factor is set, a value proportional to the default damping value is applied during force control.
-
The damping factor is applied only during force control. It is applied as a default value for compliance control.
-
This function is supported only for the M series. It cannot be used for A series and H series.
Warning
-
If the damping factor is set to less than 1.0, the robot may vibrate depending on the contact surface. Please use it carefully.
Return
|
Value |
Description |
|---|---|
|
0 |
Success |
|
Negative value |
Error |
Exception
|
Exception |
Description |
|---|---|
|
DR_Error (DR_ERROR_TYPE) |
Parameter data type error occurred |
|
DR_Error (DR_ERROR_VALUE) |
Parameter value is invalid |
|
DR_Error (DR_ERROR_RUNTIME) |
C extension module error occurred |
|
DR_Error (DR_ERROR_STOP) |
Program terminated forcefully |
Example
# 1. Move to initial posj
q0 = posj(0.0, 0.0, 90.0, 0.0, 90.0, 0.0)
set_velj(30.0)
set_accj(60.0)
movej(q0)
# 2. Start force control (apply -20N force along Base–z direction)
k_d = [3000.0, 3000.0, 3000.0, 200.0, 200.0, 200.0]
task_compliance_ctrl(k_d)
force_desired = 20.0
f_d = [0.0, 0.0, -force_desired, 0.0, 0.0, 0.0]
f_dir = [0, 0, 1, 0, 0, 0]
d_f = [1.0, 1.0, 0.8, 1.0, 1.0, 1.0]
set_desired_force(f_d, f_dir)
set_damping_factor(d_f)
wait(2.0)
release_force()
wait(0.5)
release_compliance_ctrl()