Plane: use enum FlightMode in more places

This commit is contained in:
Andrew Tridgell 2012-12-01 08:15:48 +11:00
parent 4b944ae6c4
commit 81660d07fd
4 changed files with 26 additions and 15 deletions

View File

@ -315,7 +315,7 @@ static bool usb_connected;
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// This is the state of the flight control system // This is the state of the flight control system
// There are multiple states defined such as MANUAL, FBW-A, AUTO // There are multiple states defined such as MANUAL, FBW-A, AUTO
byte control_mode = INITIALISING; enum FlightMode control_mode = INITIALISING;
// Used to maintain the state of the previous control switch position // Used to maintain the state of the previous control switch position
// This is set to -1 when we need to re-read the switch // This is set to -1 when we need to re-read the switch
byte oldSwitchPosition; byte oldSwitchPosition;
@ -1199,6 +1199,10 @@ static void update_current_flight_mode(void)
break; break;
//roll: -13788.000, pitch: -13698.000, thr: 0.000, rud: -13742.000 //roll: -13788.000, pitch: -13698.000, thr: 0.000, rud: -13742.000
case INITIALISING:
case AUTO:
// handled elsewhere
break;
} }
} }
} }
@ -1209,19 +1213,26 @@ static void update_navigation()
// ------------------------------------------------------------------------ // ------------------------------------------------------------------------
// distance and bearing calcs only // distance and bearing calcs only
if(control_mode == AUTO) { switch(control_mode) {
case AUTO:
verify_commands(); verify_commands();
}else{ break;
case LOITER:
case RTL:
case GUIDED:
update_loiter();
calc_bearing_error();
break;
switch(control_mode) { case MANUAL:
case LOITER: case INITIALISING:
case RTL: case FLY_BY_WIRE_A:
case GUIDED: case FLY_BY_WIRE_B:
update_loiter(); case CIRCLE:
calc_bearing_error(); case STABILIZE:
break; // nothing to do
break;
}
} }
} }

View File

@ -1148,7 +1148,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case AUTO: case AUTO:
case RTL: case RTL:
case LOITER: case LOITER:
set_mode(packet.custom_mode); set_mode((enum FlightMode)packet.custom_mode);
break; break;
} }

View File

@ -29,7 +29,7 @@ static void read_control_switch()
return; return;
} }
set_mode(flight_modes[switchPosition]); set_mode((enum FlightMode)(flight_modes[switchPosition].get()));
oldSwitchPosition = switchPosition; oldSwitchPosition = switchPosition;
prev_WP = current_loc; prev_WP = current_loc;

View File

@ -332,7 +332,7 @@ static void startup_ground(void)
gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY.")); gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY."));
} }
static void set_mode(byte mode) static void set_mode(enum FlightMode mode)
{ {
if(control_mode == mode) { if(control_mode == mode) {
// don't switch modes if we are already in the correct mode. // don't switch modes if we are already in the correct mode.