Browse Source

Copter: Do not use the Delay method wrapper.

master
murata 7 years ago committed by Randy Mackay
parent
commit
a970eacf49
  1. 3
      ArduCopter/Copter.h
  2. 6
      ArduCopter/compat.cpp
  3. 14
      ArduCopter/esc_calibration.cpp

3
ArduCopter/Copter.h

@ -715,9 +715,6 @@ private: @@ -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();

6
ArduCopter/compat.cpp

@ -1,6 +0,0 @@ @@ -1,6 +0,0 @@
#include "Copter.h"
void Copter::delay(uint32_t ms)
{
hal.scheduler->delay(ms);
}

14
ArduCopter/esc_calibration.cpp

@ -27,7 +27,7 @@ void Copter::esc_calibration_startup_check() @@ -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() @@ -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() @@ -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() @@ -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() @@ -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() @@ -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() @@ -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
}

Loading…
Cancel
Save