Browse Source

Sub: Send a heartbeat on mode change

master
Michael du Breuil 6 years ago committed by Tom Pittenger
parent
commit
e22bda2527
  1. 1
      ArduSub/flight_mode.cpp

1
ArduSub/flight_mode.cpp

@ -71,6 +71,7 @@ bool Sub::set_mode(control_mode_t mode, mode_reason_t reason) @@ -71,6 +71,7 @@ bool Sub::set_mode(control_mode_t mode, mode_reason_t reason)
control_mode = mode;
control_mode_reason = reason;
logger.Write_Mode(control_mode, control_mode_reason);
gcs().send_message(MSG_HEARTBEAT);
// update notify object
notify_flight_mode(control_mode);

Loading…
Cancel
Save