diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 428ea3dfef..31c29b4d33 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -124,7 +124,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) interference_pct[i] = 0.0f; } - EXPECT_DELAY(hal, 5000); + EXPECT_DELAY_MS(5000); // enable motors and pass through throttle init_rc_out(); @@ -137,7 +137,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) // main run while there is no user input and the compass is healthy while (command_ack_start == command_ack_counter && compass.healthy() && motors->armed()) { - EXPECT_DELAY(hal, 5000); + EXPECT_DELAY_MS(5000); // 50hz loop if (millis() - last_run_time < 20) { diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 6b0e573125..adc1cd0511 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -25,7 +25,7 @@ void Copter::motor_test_output() return; } - EXPECT_DELAY(hal, 2000); + EXPECT_DELAY_MS(2000); // check for test timeout uint32_t now = AP_HAL::millis(); @@ -148,7 +148,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t moto // start test ap.motor_test = true; - EXPECT_DELAY(hal, 3000); + EXPECT_DELAY_MS(3000); // enable and arm motors if (!motors->armed()) { init_rc_out();