mirror of https://github.com/ArduPilot/ardupilot
Tracker: Send a heartbeat on mode change
This commit is contained in:
parent
06e7120b4b
commit
99872ea9e2
|
@ -235,6 +235,7 @@ void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason)
|
|||
|
||||
// log mode change
|
||||
logger.Write_Mode(control_mode, reason);
|
||||
gcs().send_message(MSG_HEARTBEAT);
|
||||
|
||||
nav_status.bearing = ahrs.yaw_sensor * 0.01f;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue