mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: emit throttle armed and throttle disarmed statustexts
This commit is contained in:
parent
1c4b5b0d73
commit
55a9165624
@ -344,6 +344,8 @@ bool AP_Arming_Rover::arm(AP_Arming::Method method, const bool do_arming_checks)
|
||||
|
||||
change_arm_state();
|
||||
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -363,6 +365,8 @@ bool AP_Arming_Rover::disarm(void)
|
||||
// only log if disarming was successful
|
||||
change_arm_state();
|
||||
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Throttle disarmed");
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user