mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Landing: emit DEPLOY gcs text only if not already deployed
This commit is contained in:
parent
71017cb288
commit
2dacafe0f3
@ -122,14 +122,15 @@ void AP_LandingGear::deploy()
|
|||||||
// set servo PWM to deployed position
|
// set servo PWM to deployed position
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::Limit::MAX);
|
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::Limit::MAX);
|
||||||
|
|
||||||
|
// send message only if output has been configured
|
||||||
|
if (!_deployed &&
|
||||||
|
SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
|
||||||
|
gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: DEPLOY");
|
||||||
|
}
|
||||||
|
|
||||||
// set deployed flag
|
// set deployed flag
|
||||||
_deployed = true;
|
_deployed = true;
|
||||||
_have_changed = true;
|
_have_changed = true;
|
||||||
|
|
||||||
// send message only if output has been configured
|
|
||||||
if (SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
|
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: DEPLOY");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/// retract - retract landing gear
|
/// retract - retract landing gear
|
||||||
|
Loading…
Reference in New Issue
Block a user