Browse Source

Rover: move update_mission to APMrover2.cpp

mission-4.1.18
Randy Mackay 6 years ago
parent
commit
7a80eb0169
  1. 10
      APMrover2/APMrover2.cpp
  2. 4
      APMrover2/Rover.h
  3. 11
      APMrover2/commands_logic.cpp

10
APMrover2/APMrover2.cpp

@ -329,4 +329,14 @@ void Rover::update_current_mode(void) @@ -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);

4
APMrover2/Rover.h

@ -392,14 +392,12 @@ private: @@ -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;

11
APMrover2/commands_logic.cpp

@ -1,11 +0,0 @@ @@ -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();
}
}
}
Loading…
Cancel
Save