diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index 2e31f31b7e..dcb78800aa 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -329,4 +329,14 @@ void Rover::update_current_mode(void) control_mode->update(); } +// update mission including starting or stopping commands. called by scheduler at 10Hz +void Rover::update_mission(void) +{ + if (control_mode == &mode_auto) { + if (ahrs.home_is_set() && mode_auto.mission.num_commands() > 1) { + mode_auto.mission.update(); + } + } +} + AP_HAL_MAIN_CALLBACKS(&rover); diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index e2638f9099..97d6ea75e8 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -392,14 +392,12 @@ private: void one_second_loop(void); void update_GPS(void); void update_current_mode(void); + void update_mission(void); // balance_bot.cpp void balancebot_pitch_control(float &throttle); bool is_balancebot() const; - // commands_logic.cpp - void update_mission(void); - // commands.cpp bool set_home_to_current_location(bool lock) WARN_IF_UNUSED; bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED; diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp deleted file mode 100644 index 88649ef57d..0000000000 --- a/APMrover2/commands_logic.cpp +++ /dev/null @@ -1,11 +0,0 @@ -#include "Rover.h" - -// update mission including starting or stopping commands. called by scheduler at 10Hz -void Rover::update_mission(void) -{ - if (control_mode == &mode_auto) { - if (ahrs.home_is_set() && mode_auto.mission.num_commands() > 1) { - mode_auto.mission.update(); - } - } -}