Copter: Add 'Unknown' to the flight mode
This commit is contained in:
parent
637aec0085
commit
926a76c2b4
@ -281,22 +281,22 @@
|
||||
//
|
||||
|
||||
#ifndef FLIGHT_MODE_1
|
||||
# define FLIGHT_MODE_1 Mode::Number::STABILIZE
|
||||
# define FLIGHT_MODE_1 Mode::Number::UNKNOWN
|
||||
#endif
|
||||
#ifndef FLIGHT_MODE_2
|
||||
# define FLIGHT_MODE_2 Mode::Number::STABILIZE
|
||||
# define FLIGHT_MODE_2 Mode::Number::UNKNOWN
|
||||
#endif
|
||||
#ifndef FLIGHT_MODE_3
|
||||
# define FLIGHT_MODE_3 Mode::Number::STABILIZE
|
||||
# define FLIGHT_MODE_3 Mode::Number::UNKNOWN
|
||||
#endif
|
||||
#ifndef FLIGHT_MODE_4
|
||||
# define FLIGHT_MODE_4 Mode::Number::STABILIZE
|
||||
# define FLIGHT_MODE_4 Mode::Number::UNKNOWN
|
||||
#endif
|
||||
#ifndef FLIGHT_MODE_5
|
||||
# define FLIGHT_MODE_5 Mode::Number::STABILIZE
|
||||
# define FLIGHT_MODE_5 Mode::Number::UNKNOWN
|
||||
#endif
|
||||
#ifndef FLIGHT_MODE_6
|
||||
# define FLIGHT_MODE_6 Mode::Number::STABILIZE
|
||||
# define FLIGHT_MODE_6 Mode::Number::UNKNOWN
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -179,6 +179,10 @@ Mode *Copter::mode_from_mode_num(const Mode::Number mode)
|
||||
break;
|
||||
#endif
|
||||
|
||||
case Mode::Number::UNKNOWN:
|
||||
// Do not set the flight mode
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@ -238,8 +242,10 @@ bool Copter::gcs_mode_enabled(const Mode::Number mode_num)
|
||||
if (new_flightmode != nullptr) {
|
||||
mode_change_failed(new_flightmode, "GCS entry disabled (FLTMODE_GCSBLOCK)");
|
||||
} else {
|
||||
if (mode_num != Mode::Number::UNKNOWN) {
|
||||
notify_no_such_mode((uint8_t)mode_num);
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
@ -283,7 +289,9 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
|
||||
|
||||
Mode *new_flightmode = mode_from_mode_num(mode);
|
||||
if (new_flightmode == nullptr) {
|
||||
if (mode != Mode::Number::UNKNOWN) {
|
||||
notify_no_such_mode((uint8_t)mode);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -100,6 +100,7 @@ public:
|
||||
AUTOROTATE = 26, // Autonomous autorotation
|
||||
AUTO_RTL = 27, // Auto RTL, this is not a true mode, AUTO will report as this mode if entered to perform a DO_LAND_START Landing sequence
|
||||
TURTLE = 28, // Flip over after crash
|
||||
UNKNOWN = 255, // unknown
|
||||
|
||||
// Mode number 127 reserved for the "drone show mode" in the Skybrush
|
||||
// fork at https://github.com/skybrush-io/ardupilot
|
||||
|
Loading…
Reference in New Issue
Block a user