Skip to content

Commit 0f2424a

Browse files
committed
Increase required PolyScope 5 version to 5.23.0
Now that 5.23.0 is released, we can increase the version requirement properly.
1 parent 650c636 commit 0f2424a

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

resources/external_control.urscript

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -270,7 +270,7 @@ thread torqueThread():
270270
textmsg("ExternalControl: Starting torque thread")
271271
while control_mode == MODE_TORQUE:
272272
torque = cmd_torque
273-
{% if ROBOT_SOFTWARE_VERSION >= v5.22.0 %} # ToDo: Increase to 5.23.0 once released
273+
{% if ROBOT_SOFTWARE_VERSION >= v5.23.0 %}
274274
{% if ROBOT_SOFTWARE_VERSION < v6.0.0 %}
275275
direct_torque(torque, friction_comp=friction_compensation_enabled)
276276
{% elif ROBOT_SOFTWARE_VERSION >= v10.11.0 %}
@@ -688,7 +688,7 @@ end
688688
thread PDControlThread():
689689
while control_mode == MODE_PD_CONTROLLER_JOINT or control_mode == MODE_PD_CONTROLLER_TASK:
690690
local q_err = cmd_servo_q - get_actual_joint_positions()
691-
{% if ROBOT_SOFTWARE_VERSION >= v5.22.0 %} # ToDo: Increase to 5.23.0 once released
691+
{% if ROBOT_SOFTWARE_VERSION >= v5.23.0 %}
692692
{% if ROBOT_SOFTWARE_VERSION < v6.0.0 %}
693693
local tau = pd_controller_gains.kp * q_err - pd_controller_gains.kd * get_actual_joint_speeds()
694694
tau = clamp_array(tau, max_joint_torques)

0 commit comments

Comments
 (0)