mirror of https://github.com/ArduPilot/ardupilot
Rover: make bad-mode-number notification consistent across vehicles
This commit is contained in:
parent
ac05a66a54
commit
591c7d55c7
|
@ -248,6 +248,7 @@ bool Rover::set_mode(const uint8_t new_mode, ModeReason reason)
|
|||
static_assert(sizeof(Mode::Number) == sizeof(new_mode), "The new mode can't be mapped to the vehicles mode number");
|
||||
Mode *mode = rover.mode_from_mode_num((enum Mode::Number)new_mode);
|
||||
if (mode == nullptr) {
|
||||
notify_no_such_mode(new_mode);
|
||||
return false;
|
||||
}
|
||||
return rover.set_mode(*mode, reason);
|
||||
|
|
Loading…
Reference in New Issue