Browse Source

Plane: emit throttle armed and throttle disarmed statustexts

master
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
8fdc2a1bad
  1. 5
      ArduPlane/system.cpp

5
ArduPlane/system.cpp

@ -472,6 +472,9 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c @@ -472,6 +472,9 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
}
change_arm_state();
gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
return true;
}
@ -506,5 +509,7 @@ bool AP_Arming_Plane::disarm(void) @@ -506,5 +509,7 @@ bool AP_Arming_Plane::disarm(void)
}
#endif
gcs().send_text(MAV_SEVERITY_INFO, "Throttle disarmed");
return true;
}

Loading…
Cancel
Save