mirror of
https://github.com/OpenSolo/OpenSolo.git
synced 2025-05-29 13:00:12 +02:00
MODES: Add newer ArduCopter flight modes
Several new flight modes have been added to ArduCopter since the Solo was created. This patch addes to the enumerations: - Throw Mode - ADS-B Aviodance (not a user mode) - Guided w/ no GPS - Smart RTL
This commit is contained in:
parent
cc732e2d52
commit
77d268a388
@ -46,22 +46,26 @@ void FlightManager::init()
|
|||||||
const char *FlightManager::flightModeStr(FlightMode m)
|
const char *FlightManager::flightModeStr(FlightMode m)
|
||||||
{
|
{
|
||||||
switch (m) {
|
switch (m) {
|
||||||
case STABILIZE: return "Stabilize";
|
case STABILIZE: return "Stabilize";
|
||||||
case ACRO: return "Acro";
|
case ACRO: return "Acro";
|
||||||
case ALT_HOLD: return "Alt Hold";
|
case ALT_HOLD: return "Alt Hold";
|
||||||
case AUTO: return "Auto";
|
case AUTO: return "Auto";
|
||||||
case GUIDED: return "Guided";
|
case GUIDED: return "Guided";
|
||||||
case LOITER: return "Loiter";
|
case LOITER: return "Loiter";
|
||||||
case RTL: return "Return to Home";
|
case RTL: return "Return to Home";
|
||||||
case CIRCLE: return "Circle";
|
case CIRCLE: return "Circle";
|
||||||
case LAND: return "Land";
|
case LAND: return "Land";
|
||||||
case OF_LOITER: return "OF Loiter";
|
case DRIFT: return "Drift";
|
||||||
case DRIFT: return "Drift";
|
case SPORT: return "Sport";
|
||||||
case SPORT: return "Sport";
|
case FLIP: return "Flip";
|
||||||
case FLIP: return "Flip";
|
case AUTOTUNE: return "Auto Tune";
|
||||||
case AUTOTUNE: return "Auto Tune";
|
case POSHOLD: return "Pos Hold";
|
||||||
case POSHOLD: return "Pos Hold";
|
case BRAKE: return "Brake";
|
||||||
default: return "Unknown";
|
case THROW: return "Throw";
|
||||||
|
case AVOID_ADSB: return "ADS-B AVOID";
|
||||||
|
case GUIDED_NOGPS: return "Guided No GPS";
|
||||||
|
case SMART_RTL: return "Smart RTL";
|
||||||
|
default: return "Unknown";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -17,24 +17,26 @@ class FlightManager
|
|||||||
public:
|
public:
|
||||||
// in sync with github.com/diydrones/ardupilot/blob/master/ArduCopter/defines.h
|
// in sync with github.com/diydrones/ardupilot/blob/master/ArduCopter/defines.h
|
||||||
enum FlightMode {
|
enum FlightMode {
|
||||||
STABILIZE = 0, // hold level position
|
STABILIZE = 0, // manual airframe angle with manual throttle
|
||||||
ACRO = 1, // rate control
|
ACRO = 1, // manual body-frame angular rate with manual throttle
|
||||||
ALT_HOLD = 2, // AUTO control
|
ALT_HOLD = 2, // manual airframe angle with automatic throttle
|
||||||
AUTO = 3, // AUTO control
|
AUTO = 3, // fully automatic waypoint control using mission commands
|
||||||
GUIDED = 4, // AUTO control
|
GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
|
||||||
LOITER = 5, // Hold a single location
|
LOITER = 5, // automatic horizontal acceleration with automatic throttle
|
||||||
RTL = 6, // AUTO control
|
RTL = 6, // automatic return to launching point
|
||||||
CIRCLE = 7, // AUTO control
|
CIRCLE = 7, // automatic circular flight with automatic throttle
|
||||||
LAND = 9, // AUTO control
|
LAND = 9, // automatic landing with horizontal position control
|
||||||
OF_LOITER = 10, // Hold a single location using optical flow sensor
|
DRIFT = 11, // semi-automous position, yaw and throttle control
|
||||||
DRIFT = 11, // DRIFT mode (Note: 12 is no longer used)
|
SPORT = 13, // manual earth-frame angular rate control with manual throttle
|
||||||
SPORT = 13, // earth frame rate control
|
FLIP = 14, // automatically flip the vehicle on the roll axis
|
||||||
FLIP = 14, // flip the vehicle on the roll axis
|
AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains
|
||||||
AUTOTUNE = 15, // autotune the vehicle's roll and pitch gains
|
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
|
||||||
POSHOLD = 16, // position hold with manual override
|
BRAKE = 17, // full-brake using inertial/GPS system, no pilot input
|
||||||
STOP = 17, // full-stop using inertial/GPS system, no pilot input. also referred to as BRAKE
|
THROW = 18, // throw to launch mode using inertial/GPS system, no pilot input
|
||||||
};
|
AVOID_ADSB = 19, // automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft
|
||||||
//const int NUM_MODES = STOP+1;
|
GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude
|
||||||
|
SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps
|
||||||
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* XXX: the MAVLINK_MSG_ID_STATUSTEXT indicates that the MAV_SEVERITY enum
|
* XXX: the MAVLINK_MSG_ID_STATUSTEXT indicates that the MAV_SEVERITY enum
|
||||||
@ -102,11 +104,11 @@ public:
|
|||||||
}
|
}
|
||||||
static const char *flightModeStr(FlightMode m);
|
static const char *flightModeStr(FlightMode m);
|
||||||
static bool flightModeIsAutonomous(FlightMode m) {
|
static bool flightModeIsAutonomous(FlightMode m) {
|
||||||
return (m == AUTO || m == GUIDED || m == LOITER || m == RTL || m == CIRCLE || m == DRIFT || m == POSHOLD || m == STOP );
|
return (m == AUTO || m == GUIDED || m == LOITER || m == RTL || m == CIRCLE || m == DRIFT || m == POSHOLD || m == BRAKE || m == THROW || m == AVOID_ADSB || m == GUIDED_NOGPS || m == SMART_RTL );
|
||||||
}
|
}
|
||||||
|
|
||||||
ALWAYS_INLINE bool currentFlightModeManual() const {
|
ALWAYS_INLINE bool currentFlightModeManual() const {
|
||||||
return !flightModeIsAutonomous(mode) && !(mode==OF_LOITER); // OF_LOITER is a deprecated mode
|
return !flightModeIsAutonomous(mode);
|
||||||
}
|
}
|
||||||
|
|
||||||
ALWAYS_INLINE bool currentFlightModeRequiresGPS() const {
|
ALWAYS_INLINE bool currentFlightModeRequiresGPS() const {
|
||||||
|
Loading…
x
Reference in New Issue
Block a user