Browse Source

AP_Landing: emit DEPLOY gcs text only if not already deployed

mission-4.1.18
Peter Barker 5 years ago committed by Randy Mackay
parent
commit
121accf392
  1. 11
      libraries/AP_LandingGear/AP_LandingGear.cpp

11
libraries/AP_LandingGear/AP_LandingGear.cpp

@ -122,14 +122,15 @@ void AP_LandingGear::deploy() @@ -122,14 +122,15 @@ void AP_LandingGear::deploy()
// set servo PWM to deployed position
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
// set deployed flag
_deployed = true;
_have_changed = true;
// send message only if output has been configured
if (SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
if (!_deployed &&
SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: DEPLOY");
}
// set deployed flag
_deployed = true;
_have_changed = true;
}
/// retract - retract landing gear

Loading…
Cancel
Save