mirror of https://github.com/ArduPilot/ardupilot
Plane: Send a heartbeat on mode change
This commit is contained in:
parent
242096b65e
commit
39c35814ec
|
@ -301,6 +301,7 @@ bool Plane::set_mode(Mode &new_mode, const mode_reason_t reason)
|
||||||
// log and notify mode change
|
// log and notify mode change
|
||||||
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
|
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
|
||||||
notify_mode(*control_mode);
|
notify_mode(*control_mode);
|
||||||
|
gcs().send_message(MSG_HEARTBEAT);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue