715715
716716# Thread to receive one shot script commands, the commands shouldn't be blocking
717717thread script_commands():
718+ last_force_mode_set_damping = -1.0 # Negative damping will give a runtime expection
719+ last_force_mode_set_gain_scaling = -1.0 # Negative scaling will give a runtime expection
718720 while control_mode > MODE_STOPPED:
719721 raw_command = socket_read_binary_integer(SCRIPT_COMMAND_DATA_DIMENSION, "script_command_socket", 0)
720722 if raw_command[0] > 0:
@@ -734,12 +736,23 @@ thread script_commands():
734736 wrench = [raw_command[14] / MULT_jointstate, raw_command[15] / MULT_jointstate, raw_command[16] / MULT_jointstate, raw_command[17] / MULT_jointstate, raw_command[18] / MULT_jointstate, raw_command[19] / MULT_jointstate]
735737 force_type = raw_command[20] / MULT_jointstate
736738 force_limits = [raw_command[21] / MULT_jointstate, raw_command[22] / MULT_jointstate, raw_command[23] / MULT_jointstate, raw_command[24] / MULT_jointstate, raw_command[25] / MULT_jointstate, raw_command[26] / MULT_jointstate]
737- force_mode_set_damping(raw_command[27] / MULT_jointstate)
739+
740+ # Only update the forcemode damping if changed
741+ local new_force_mode_set_damping = raw_command[27] / MULT_jointstate
742+ if new_force_mode_set_damping != last_force_mode_set_damping:
743+ force_mode_set_damping(new_force_mode_set_damping)
744+ last_force_mode_set_damping = new_force_mode_set_damping
745+ end
738746 # Check whether script is running on CB3 or e-series. Gain scaling can only be set on e-series robots.
739747 # step time = 0.008: CB3 robot
740748 # Step time = 0.002: e-series robot
741749 if (get_steptime() < 0.008):
742- force_mode_set_gain_scaling(raw_command[28] / MULT_jointstate)
750+ # Only update the forcemode damping if changed
751+ local new_force_mode_set_gain_scaling = raw_command[28] / MULT_jointstate
752+ if new_force_mode_set_gain_scaling != last_force_mode_set_gain_scaling:
753+ force_mode_set_gain_scaling(new_force_mode_set_gain_scaling)
754+ last_force_mode_set_gain_scaling = new_force_mode_set_gain_scaling
755+ end
743756 end
744757 force_mode(task_frame, selection_vector, wrench, force_type, force_limits)
745758 elif command == END_FORCE_MODE:
0 commit comments