this sets a minimum distance to use the fixed wing approach logic. It
is an alternative to just disabling the approach with Q_OPTIONS which
some users do to avoid some short distance problems. This allows the
approach to still be used for longer distances in QRTL but have it
disabled for shorter distances
Plane: Fix description for TECS_BCK_PIT_LIM
Plane: Add diagnostics logging for VTOL upper pitch limit calc
Plane: Rework "Prevent overloading quadplane wing during VTOL braking"
Implement an independent speed scaler calculation. During VTOL modes the plane surface speed scaler does not follow a 1/IAS function at low airspeed.
this fixes a bug where TECS maintains its slow integrator while in a
VTOL hover mode in AUTO or GUIDED.
Among other things this affects PAYLOAD_PLACE and
DO_VTOL_TRANSITION. In those states the height can change while
hovering outside the control of TECS. When TECS regains control in a
fwd transition then can lead to a very large height loss or gain until
the TECS integrator can catch up
During POSITION1 back-transiton we scale the MC angle P gains with
airspeed to reduce the chance of oscillations. At higher airspeeds the
fixed wing controller dominates so we should use the fixed wing angle
P gain.
this is equivalent to copters WP_NAVALT_MIN parameter for takeoff. Not
implemented for land yet
this is useful for vehicles with significant GPS velocity noise on
takeoff, preventing dragging the landing gear
when we arm in guided mode then enter a special guided_wait_takeoff
state. We keep motors suppressed until one of the following happens
1) disarm
2) guided takeoff command
3) change to AUTO with a takeoff waypoint as first nav waypoint
4) change to another mode
while in this state we don't go to throttle unlimited, and will refuse
a change to AUTO mode if the first waypoint is not a takeoff. If we
try to switch to RTL then we will instead use QLAND
This state is needed to cope with the takeoff sequence used by QGC on
common controllers such as the MX16, which do this on a "takeoff"
swipe:
- changes mode to GUIDED
- arms
- changes mode to AUTO
AP_Logger.h is a nexus of includes; while this is being improved over
time, there's no reason for the library headers to include AP_Logger.h
as the logger itself is access by singleton and the structures are in
LogStructure.h
This necessitated moving The PID_Info structure out of AP_Logger's
namespace. This cleans up a pretty nasty bit - that structure is
definitely not simply used for logging, but also used to pass pid
information around to controllers!
There are a lot of patches in here because AP_Logger.h, acting as a
nexus, was providing transitive header file inclusion in many (some
unlikely!) places.
this improves 4 things in the POSITION1 controller based on logs from
4.2.0beta2. The changes are designed to increase the tolerance to
an incorrect value for Q_TRANS_DECEL, reducing landing overshoot
1) we fix the initialisation of the acceleration. The
init_xy_controller() function assumes zero accel, so we need to
call set_accel_desired_xy_cmss() just after that init to get the
correct accel. Thanks to Leonard for this fix
2) if we decel more than expected due to too low Q_TRANS_DECEL we
need to reduce the target speed, rather than putting the nose down
3) lower the default Q_P_JERK_XY to a value more appropriate for most
quadplanes (Leonard suggested a value of 2)
4) fixed the pitch envelope from Q_BACKTRANS_MS to start after the
airbrake phase is complete