diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 9e8a73e740..56d4653cbb 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -442,7 +442,6 @@ private: // compat.cpp void delay(uint32_t ms); - void mavlink_delay(uint32_t ms); // control_modes.cpp Mode *control_mode_from_num(enum mode num); diff --git a/APMrover2/compat.cpp b/APMrover2/compat.cpp index b122a95f1c..75686d5d30 100644 --- a/APMrover2/compat.cpp +++ b/APMrover2/compat.cpp @@ -4,8 +4,3 @@ void Rover::delay(uint32_t ms) { hal.scheduler->delay(ms); } - -void Rover::mavlink_delay(uint32_t ms) -{ - hal.scheduler->delay(ms); -}