diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 5a12422241..f8ea13a98d 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -715,9 +715,6 @@ private: // compassmot.cpp MAV_RESULT mavlink_compassmot(mavlink_channel_t chan); - // compat.cpp - void delay(uint32_t ms); - // crash_check.cpp void crash_check(); void parachute_check(); diff --git a/ArduCopter/compat.cpp b/ArduCopter/compat.cpp deleted file mode 100644 index 51546c4384..0000000000 --- a/ArduCopter/compat.cpp +++ /dev/null @@ -1,6 +0,0 @@ -#include "Copter.h" - -void Copter::delay(uint32_t ms) -{ - hal.scheduler->delay(ms); -} diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index 02ff1aa428..91deaea3c3 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -27,7 +27,7 @@ void Copter::esc_calibration_startup_check() // delay up to 2 second for first radio input uint8_t i = 0; while ((i++ < 100) && (last_radio_update_ms == 0)) { - delay(20); + hal.scheduler->delay(20); read_radio(); } @@ -52,7 +52,7 @@ void Copter::esc_calibration_startup_check() // turn on esc calibration notification AP_Notify::flags.esc_calibration = true; // block until we restart - while(1) { delay(5); } + while(1) { hal.scheduler->delay(5); } } break; case ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH: @@ -112,7 +112,7 @@ void Copter::esc_calibration_passthrough() printed_msg = true; } esc_calibration_notify(); - delay(3); + hal.scheduler->delay(3); } // arm motors @@ -129,7 +129,7 @@ void Copter::esc_calibration_passthrough() // we run at high rate to make oneshot ESCs happy. Normal ESCs // will only see pulses at the RC_SPEED - delay(3); + hal.scheduler->delay(3); // pass through to motors SRV_Channels::cork(); @@ -168,7 +168,7 @@ void Copter::esc_calibration_auto() printed_msg = true; } esc_calibration_notify(); - delay(3); + hal.scheduler->delay(3); } // arm and enable motors @@ -188,7 +188,7 @@ void Copter::esc_calibration_auto() motors->set_throttle_passthrough_for_esc_calibration(1.0f); SRV_Channels::push(); esc_calibration_notify(); - delay(3); + hal.scheduler->delay(3); } // block until we restart @@ -197,7 +197,7 @@ void Copter::esc_calibration_auto() motors->set_throttle_passthrough_for_esc_calibration(0.0f); SRV_Channels::push(); esc_calibration_notify(); - delay(3); + hal.scheduler->delay(3); } #endif // FRAME_CONFIG != HELI_FRAME }