|
|
|
@ -92,26 +92,25 @@ enum aux_sw_func {
@@ -92,26 +92,25 @@ enum aux_sw_func {
|
|
|
|
|
#define HIL_MODE_DISABLED 0 |
|
|
|
|
#define HIL_MODE_SENSORS 1 |
|
|
|
|
|
|
|
|
|
// Auto Pilot modes
|
|
|
|
|
// ----------------
|
|
|
|
|
#define STABILIZE 0 // hold level position
|
|
|
|
|
#define ACRO 1 // rate control
|
|
|
|
|
#define ALT_HOLD 2 // AUTO control
|
|
|
|
|
#define AUTO 3 // AUTO control
|
|
|
|
|
#define GUIDED 4 // AUTO control
|
|
|
|
|
#define LOITER 5 // Hold a single location
|
|
|
|
|
#define RTL 6 // AUTO control
|
|
|
|
|
#define CIRCLE 7 // AUTO control
|
|
|
|
|
#define LAND 9 // AUTO control
|
|
|
|
|
#define OF_LOITER 10 // Hold a single location using optical flow sensor
|
|
|
|
|
#define DRIFT 11 // DRIFT mode (Note: 12 is no longer used)
|
|
|
|
|
#define SPORT 13 // earth frame rate control
|
|
|
|
|
#define FLIP 14 // flip the vehicle on the roll axis
|
|
|
|
|
#define AUTOTUNE 15 // autotune the vehicle's roll and pitch gains
|
|
|
|
|
#define POSHOLD 16 // position hold with manual override
|
|
|
|
|
#define STOP 17 // Full-Stop using inertial/GPS system, no pilot input
|
|
|
|
|
#define NUM_MODES 18 |
|
|
|
|
|
|
|
|
|
// Auto Pilot Modes enumeration
|
|
|
|
|
enum autopilot_modes { |
|
|
|
|
STABILIZE = 0, // 0, manual airframe angle with manual throttle
|
|
|
|
|
ACRO, // 1, manual body-frame angular rate with manual throttle
|
|
|
|
|
ALT_HOLD, // 2, manual airframe angle with automatic throttle
|
|
|
|
|
AUTO, // 3, fully automatic waypoint control
|
|
|
|
|
GUIDED, // 4, fully automatic fly to coordinate or fly at velocity/direction
|
|
|
|
|
LOITER, // 5, automatic horizontal acceleration with automatic throttle
|
|
|
|
|
RTL, // 6, automatic return to launching point
|
|
|
|
|
CIRCLE, // 7, automatic circular flight with automatic throttle
|
|
|
|
|
LAND = 9, // 9, automatic landing with horizontal position control
|
|
|
|
|
OF_LOITER, // 10, automatic position control using optical flow sensor
|
|
|
|
|
DRIFT, // 11, semi-automatic position, yaw and throttle control
|
|
|
|
|
SPORT = 13, // 13, manual earth-frame angular rate control with manual throttle
|
|
|
|
|
FLIP, // 14, automatically flip the vehicle on the roll axis
|
|
|
|
|
AUTOTUNE, // 15, automatically tune the vehicle's roll and pitch gains
|
|
|
|
|
POSHOLD, // 16, automatic position hold with manual override, with automatic throttle
|
|
|
|
|
STOP // 17, full-stop using inertial/GPS system, no pilot input
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
// Tuning enumeration
|
|
|
|
|
enum tuning_func { |
|
|
|
|