Browse Source

Mission: rename AUTORESET to RESTART

master
Randy Mackay 11 years ago
parent
commit
05f5164dfa
  1. 12
      libraries/AP_Mission/AP_Mission.cpp
  2. 4
      libraries/AP_Mission/AP_Mission.h

12
libraries/AP_Mission/AP_Mission.cpp

@ -15,11 +15,11 @@ const AP_Param::GroupInfo AP_Mission::var_info[] PROGMEM = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("TOTAL", 0, AP_Mission, _cmd_total, 0), AP_GROUPINFO("TOTAL", 0, AP_Mission, _cmd_total, 0),
// @Param: AUTORESET // @Param: RESTART
// @DisplayName: Reset mission on AUTO // @DisplayName: Mission Restart when entering Auto mode
// @Description: When set to 0 the mission will continue a previous AUTO mission when switching to AUTO mode. When set to 1 the mission will restart from the first waypoint each time AUTO mode is started. // @Description: Controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
// @Values: 0:Continue Mission, 1:Reset Mission // @Values: 0:Resume Mission, 1:Restart Mission
AP_GROUPINFO("AUTORESET", 1, AP_Mission, _auto_reset, 0), AP_GROUPINFO("RESTART", 1, AP_Mission, _restart, AP_MISSION_RESTART_DEFAULT),
AP_GROUPEND AP_GROUPEND
}; };
@ -105,7 +105,7 @@ void AP_Mission::resume()
/// start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start() /// start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start()
void AP_Mission::start_or_resume() void AP_Mission::start_or_resume()
{ {
if (_auto_reset) { if (_restart) {
start(); start();
} else { } else {
resume(); resume();

4
libraries/AP_Mission/AP_Mission.h

@ -35,6 +35,8 @@
#define AP_MISSION_FIRST_REAL_COMMAND 1 // command #0 reserved to hold home position #define AP_MISSION_FIRST_REAL_COMMAND 1 // command #0 reserved to hold home position
#define AP_MISSION_RESTART_DEFAULT 0 // resume the mission from the last command run by default
/// @class AP_Mission /// @class AP_Mission
/// @brief Object managing Mission /// @brief Object managing Mission
class AP_Mission { class AP_Mission {
@ -362,7 +364,7 @@ private:
// parameters // parameters
AP_Int16 _cmd_total; // total number of commands in the mission AP_Int16 _cmd_total; // total number of commands in the mission
AP_Int8 _auto_reset; // when true the mission will reset to the first command when initiated AP_Int8 _restart; // controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
// pointer to main program functions // pointer to main program functions
mission_cmd_fn_t _cmd_start_fn; // pointer to function which will be called when a new command is started mission_cmd_fn_t _cmd_start_fn; // pointer to function which will be called when a new command is started

Loading…
Cancel
Save