ArduCopter: make bad-mode-number notification consistent across vehicles
This commit is contained in:
parent
7a06c941df
commit
2d023967dc
@ -221,10 +221,9 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
|
||||
}
|
||||
#endif
|
||||
|
||||
Mode *new_flightmode = mode_from_mode_num((Mode::Number)mode);
|
||||
Mode *new_flightmode = mode_from_mode_num(mode);
|
||||
if (new_flightmode == nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_WARNING,"No such mode");
|
||||
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
|
||||
notify_no_such_mode((uint8_t)mode);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user