forked from Archive/PX4-Autopilot
mc_rate_control: always allow landing gear control
Except of course when landed and we try to put it up.
This commit is contained in:
parent
486a4b0118
commit
42af44700b
|
@ -153,8 +153,7 @@ MulticopterRateControl::Run()
|
|||
landing_gear_s landing_gear;
|
||||
|
||||
if (_landing_gear_sub.copy(&landing_gear)) {
|
||||
if (landing_gear.landing_gear != landing_gear_s::GEAR_KEEP &&
|
||||
_v_control_mode.flag_control_manual_enabled) {
|
||||
if (landing_gear.landing_gear != landing_gear_s::GEAR_KEEP) {
|
||||
if (landing_gear_s::GEAR_UP && (_landed || _maybe_landed)) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Landed, unable to retract landing gear")
|
||||
|
||||
|
|
Loading…
Reference in New Issue