allow flight modes to be setup over MAVLink

this adopts the same method of setting up flight modes over MAVLink as
APM now has

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2885 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-07-17 10:30:53 +00:00
parent 6467338f10
commit 72fc086005
4 changed files with 34 additions and 9 deletions

View File

@ -116,6 +116,9 @@ void update_events(void);
// All GPS access should be through this pointer. // All GPS access should be through this pointer.
GPS *g_gps; GPS *g_gps;
// flight modes convenience array
AP_Int8 *flight_modes = &g.flight_mode1;
#if HIL_MODE == HIL_MODE_DISABLED #if HIL_MODE == HIL_MODE_DISABLED
// real sensors // real sensors

View File

@ -17,7 +17,7 @@ public:
// The increment will prevent old parameters from being used incorrectly // The increment will prevent old parameters from being used incorrectly
// by newer code. // by newer code.
// //
static const uint16_t k_format_version = 103; static const uint16_t k_format_version = 104;
// The parameter software_type is set up solely for ground station use // The parameter software_type is set up solely for ground station use
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega) // and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
@ -102,7 +102,6 @@ public:
k_param_throttle_fs_action, k_param_throttle_fs_action,
k_param_throttle_fs_value, k_param_throttle_fs_value,
k_param_throttle_cruise, k_param_throttle_cruise,
k_param_flight_modes,
k_param_esc_calibrate, k_param_esc_calibrate,
@ -126,6 +125,18 @@ public:
k_param_heli_ext_gyro_gain, // 213 k_param_heli_ext_gyro_gain, // 213
#endif #endif
//
// 210: flight modes
//
k_param_flight_mode1,
k_param_flight_mode2,
k_param_flight_mode3,
k_param_flight_mode4,
k_param_flight_mode5,
k_param_flight_mode6,
// //
// 220: Waypoint data // 220: Waypoint data
// //
@ -194,7 +205,12 @@ public:
// Flight modes // Flight modes
// //
AP_VarA<uint8_t,6> flight_modes; AP_Int8 flight_mode1;
AP_Int8 flight_mode2;
AP_Int8 flight_mode3;
AP_Int8 flight_mode4;
AP_Int8 flight_mode5;
AP_Int8 flight_mode6;
// Radio settings // Radio settings
// //
@ -288,7 +304,12 @@ public:
throttle_fs_value (THROTTLE_FS_VALUE, k_param_throttle_fs_value, PSTR("THR_FS_VALUE")), throttle_fs_value (THROTTLE_FS_VALUE, k_param_throttle_fs_value, PSTR("THR_FS_VALUE")),
throttle_cruise (100, k_param_throttle_cruise, PSTR("TRIM_THROTTLE")), throttle_cruise (100, k_param_throttle_cruise, PSTR("TRIM_THROTTLE")),
flight_modes (k_param_flight_modes, PSTR("FLTMODE")), flight_mode1 (FLIGHT_MODE_1, k_param_flight_mode1, PSTR("FLTMODE1")),
flight_mode2 (FLIGHT_MODE_2, k_param_flight_mode2, PSTR("FLTMODE2")),
flight_mode3 (FLIGHT_MODE_3, k_param_flight_mode3, PSTR("FLTMODE3")),
flight_mode4 (FLIGHT_MODE_4, k_param_flight_mode4, PSTR("FLTMODE4")),
flight_mode5 (FLIGHT_MODE_5, k_param_flight_mode5, PSTR("FLTMODE5")),
flight_mode6 (FLIGHT_MODE_6, k_param_flight_mode6, PSTR("FLTMODE6")),
pitch_max (PITCH_MAX * 100, k_param_pitch_max, PSTR("PITCH_MAX")), pitch_max (PITCH_MAX * 100, k_param_pitch_max, PSTR("PITCH_MAX")),

View File

@ -7,7 +7,7 @@ void read_control_switch()
if (oldSwitchPosition != switchPosition){ if (oldSwitchPosition != switchPosition){
set_mode(g.flight_modes[switchPosition]); set_mode(flight_modes[switchPosition]);
oldSwitchPosition = switchPosition; oldSwitchPosition = switchPosition;
prev_WP = current_loc; prev_WP = current_loc;

View File

@ -320,7 +320,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
// look for control switch change // look for control switch change
if (_oldSwitchPosition != _switchPosition){ if (_oldSwitchPosition != _switchPosition){
mode = g.flight_modes[_switchPosition]; mode = flight_modes[_switchPosition];
mode = constrain(mode, 0, NUM_MODES-1); mode = constrain(mode, 0, NUM_MODES-1);
// update the user // update the user
@ -337,7 +337,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
mode = 0; mode = 0;
// save new mode // save new mode
g.flight_modes[_switchPosition] = mode; flight_modes[_switchPosition] = mode;
// print new mode // print new mode
print_switch(_switchPosition, mode); print_switch(_switchPosition, mode);
@ -345,7 +345,8 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
// escape hatch // escape hatch
if(Serial.available() > 0){ if(Serial.available() > 0){
g.flight_modes.save(); for (mode=0; mode<6; mode++)
flight_modes[mode].save();
print_done(); print_done();
report_flight_modes(); report_flight_modes();
return (0); return (0);
@ -962,7 +963,7 @@ void report_flight_modes()
print_divider(); print_divider();
for(int i = 0; i < 6; i++ ){ for(int i = 0; i < 6; i++ ){
print_switch(i, g.flight_modes[i]); print_switch(i, flight_modes[i]);
} }
print_blanks(2); print_blanks(2);
} }