|
|
|
@ -49,6 +49,12 @@ void ModeQRTL::run()
@@ -49,6 +49,12 @@ void ModeQRTL::run()
|
|
|
|
|
// start landing logic
|
|
|
|
|
quadplane.verify_vtol_land(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// when in approach allow stick mixing
|
|
|
|
|
if (quadplane.poscontrol.get_state() == QuadPlane::QPOS_AIRBRAKE || |
|
|
|
|
quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH) { |
|
|
|
|
plane.stabilize_stick_mixing_fbw(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
@ -83,4 +89,10 @@ bool ModeQRTL::update_target_altitude()
@@ -83,4 +89,10 @@ bool ModeQRTL::update_target_altitude()
|
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// only nudge during approach
|
|
|
|
|
bool ModeQRTL::allows_throttle_nudging() const |
|
|
|
|
{ |
|
|
|
|
return plane.quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#endif |
|
|
|
|