mirror of https://github.com/ArduPilot/ardupilot
Rover: tell the user we're not docking because we have no target
This commit is contained in:
parent
fef42ecd8c
commit
f2bfe8d21f
|
@ -60,6 +60,7 @@ bool ModeDock::_enter()
|
|||
{
|
||||
// refuse to enter the mode if dock is not in sight
|
||||
if (!rover.precland.enabled() || !rover.precland.target_acquired()) {
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Dock: target not acquired");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue