mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Revert "Tools: comment out the FETtecESC_safety_switch() function for now because it is failing"
This reverts commit d53299ecb0
.
This commit is contained in:
parent
ae615de4ce
commit
42c2f8d9f3
@ -7282,7 +7282,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
# before the motors will spin:
|
# before the motors will spin:
|
||||||
self.wait_esc_telem_rpm(
|
self.wait_esc_telem_rpm(
|
||||||
esc=mot,
|
esc=mot,
|
||||||
rpm_min=0, # FIXME: was 17640
|
rpm_min=17640,
|
||||||
rpm_max=17640,
|
rpm_max=17640,
|
||||||
minimum_duration=2,
|
minimum_duration=2,
|
||||||
timeout=5,
|
timeout=5,
|
||||||
@ -7292,7 +7292,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.set_safetyswitch_off()
|
self.set_safetyswitch_off()
|
||||||
self.wait_esc_telem_rpm(
|
self.wait_esc_telem_rpm(
|
||||||
esc=mot,
|
esc=mot,
|
||||||
rpm_min=0, # FIXME: was 17640
|
rpm_min=17640,
|
||||||
rpm_max=17640,
|
rpm_max=17640,
|
||||||
minimum_duration=2,
|
minimum_duration=2,
|
||||||
timeout=5,
|
timeout=5,
|
||||||
|
Loading…
Reference in New Issue
Block a user