mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: switch to an enum for flight modes
This commit is contained in:
parent
f7a05f577e
commit
4864d162d0
@ -97,7 +97,8 @@ static void stabilize()
|
|||||||
// Mix Stick input to allow users to override control surfaces
|
// Mix Stick input to allow users to override control surfaces
|
||||||
// -----------------------------------------------------------
|
// -----------------------------------------------------------
|
||||||
if (stick_mixing_enabled()) {
|
if (stick_mixing_enabled()) {
|
||||||
if (control_mode < FLY_BY_WIRE_A || control_mode > FLY_BY_WIRE_C) {
|
if (control_mode != FLY_BY_WIRE_A &&
|
||||||
|
control_mode != FLY_BY_WIRE_B) {
|
||||||
// do stick mixing on aileron/elevator if not in a fly by
|
// do stick mixing on aileron/elevator if not in a fly by
|
||||||
// wire mode
|
// wire mode
|
||||||
ch1_inf = (float)g.channel_roll.radio_in - (float)g.channel_roll.radio_trim;
|
ch1_inf = (float)g.channel_roll.radio_in - (float)g.channel_roll.radio_trim;
|
||||||
|
@ -43,7 +43,6 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
|||||||
case STABILIZE:
|
case STABILIZE:
|
||||||
case FLY_BY_WIRE_A:
|
case FLY_BY_WIRE_A:
|
||||||
case FLY_BY_WIRE_B:
|
case FLY_BY_WIRE_B:
|
||||||
case FLY_BY_WIRE_C:
|
|
||||||
base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
|
base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
|
||||||
break;
|
break;
|
||||||
case AUTO:
|
case AUTO:
|
||||||
@ -163,13 +162,6 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
|||||||
control_sensors_enabled |= (1<<15); // motor control
|
control_sensors_enabled |= (1<<15); // motor control
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case FLY_BY_WIRE_C:
|
|
||||||
control_sensors_enabled |= (1<<10); // 3D angular rate control
|
|
||||||
control_sensors_enabled |= (1<<11); // attitude stabilisation
|
|
||||||
control_sensors_enabled |= (1<<13); // altitude control
|
|
||||||
control_sensors_enabled |= (1<<15); // motor control
|
|
||||||
break;
|
|
||||||
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
case RTL:
|
case RTL:
|
||||||
case LOITER:
|
case LOITER:
|
||||||
@ -1153,7 +1145,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
case STABILIZE:
|
case STABILIZE:
|
||||||
case FLY_BY_WIRE_A:
|
case FLY_BY_WIRE_A:
|
||||||
case FLY_BY_WIRE_B:
|
case FLY_BY_WIRE_B:
|
||||||
case FLY_BY_WIRE_C:
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
case RTL:
|
case RTL:
|
||||||
case LOITER:
|
case LOITER:
|
||||||
|
@ -59,35 +59,18 @@
|
|||||||
#define HIL_MODE_ATTITUDE 1
|
#define HIL_MODE_ATTITUDE 1
|
||||||
#define HIL_MODE_SENSORS 2
|
#define HIL_MODE_SENSORS 2
|
||||||
|
|
||||||
// Auto Pilot modes
|
enum FlightMode {
|
||||||
// ----------------
|
MANUAL = 0,
|
||||||
#define MANUAL 0
|
CIRCLE = 1,
|
||||||
#define CIRCLE 1 // When flying sans GPS, and we loose
|
STABILIZE = 2,
|
||||||
// the radio, just circle
|
FLY_BY_WIRE_A = 5,
|
||||||
#define STABILIZE 2
|
FLY_BY_WIRE_B = 6,
|
||||||
|
AUTO = 10,
|
||||||
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal =>
|
RTL = 11,
|
||||||
// desired roll angle, left stick vertical =>
|
LOITER = 12,
|
||||||
// desired pitch angle, right stick vertical =
|
GUIDED = 15,
|
||||||
// manual throttle
|
INITIALISING = 16
|
||||||
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal =>
|
};
|
||||||
// desired roll angle, left stick vertical =>
|
|
||||||
// desired pitch angle, right stick vertical
|
|
||||||
// => desired airspeed
|
|
||||||
#define FLY_BY_WIRE_C 7 // Fly By Wire C has left stick horizontal =>
|
|
||||||
// desired roll angle, left stick vertical =>
|
|
||||||
// desired climb rate, right stick vertical =>
|
|
||||||
// desired airspeed
|
|
||||||
// Fly By Wire B and Fly By Wire C require airspeed sensor
|
|
||||||
#define AUTO 10
|
|
||||||
#define RTL 11
|
|
||||||
#define LOITER 12
|
|
||||||
//#define TAKEOFF 13 // This is not used by APM. It appears here
|
|
||||||
// for consistency with ACM
|
|
||||||
//#define LAND 14 // This is not used by APM. It appears here for
|
|
||||||
// consistency with ACM
|
|
||||||
#define GUIDED 15
|
|
||||||
#define INITIALISING 16 // in startup routines
|
|
||||||
|
|
||||||
|
|
||||||
// Commands - Note that APM now uses a subset of the MAVLink protocol
|
// Commands - Note that APM now uses a subset of the MAVLink protocol
|
||||||
|
Loading…
Reference in New Issue
Block a user