mirror of https://github.com/ArduPilot/ardupilot
Plane: Support not sending a status text on state change
This commit is contained in:
parent
45786a33e6
commit
28d4603a46
|
@ -319,7 +319,7 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
|
|||
// rising edge of delay_arming oneshot
|
||||
delay_arming = true;
|
||||
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
|
||||
send_arm_disarm_statustext("Throttle armed");
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -379,8 +379,8 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_chec
|
|||
// re-initialize speed variable used in AUTO and GUIDED for
|
||||
// DO_CHANGE_SPEED commands
|
||||
plane.new_airspeed_cm = -1;
|
||||
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Throttle disarmed");
|
||||
|
||||
send_arm_disarm_statustext("Throttle disarmed");
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue