mirror of https://github.com/ArduPilot/ardupilot
Rover: Change delay method to HAL scheduler's delay
This commit is contained in:
parent
d533d289da
commit
2ae57f8861
|
@ -298,9 +298,6 @@ private:
|
|||
bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED;
|
||||
void update_home();
|
||||
|
||||
// compat.cpp
|
||||
void delay(uint32_t ms);
|
||||
|
||||
// crash_check.cpp
|
||||
void crash_check();
|
||||
|
||||
|
|
|
@ -137,7 +137,7 @@ void Rover::startup_ground(void)
|
|||
|
||||
#if(GROUND_START_DELAY > 0)
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "<startup_ground> With delay");
|
||||
delay(GROUND_START_DELAY * 1000);
|
||||
hal.scheduler->delay(GROUND_START_DELAY * 1000);
|
||||
#endif
|
||||
|
||||
// IMU ground start
|
||||
|
|
Loading…
Reference in New Issue