From b9f3118374af4f6d749d170aa2eef98f5a8e4f72 Mon Sep 17 00:00:00 2001 From: Mark Whitehorn Date: Mon, 4 Feb 2019 10:14:01 -0700 Subject: [PATCH] Plane: allow changing Q_TRIM_PITCH in flight change float comparison to is_equal --- ArduPlane/quadplane.cpp | 9 +++++++-- ArduPlane/quadplane.h | 1 + 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index c20355aa77..2a3f0c8204 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -491,7 +491,7 @@ bool QuadPlane::setup(void) enum AP_Motors::motor_frame_class motor_class; enum Rotation rotation = ROTATION_NONE; - + /* cope with upgrade from old AP_Motors values for frame_class */ @@ -1458,7 +1458,12 @@ void QuadPlane::update(void) if (!setup()) { return; } - + + if ((ahrs_view != NULL) && !is_equal(_last_ahrs_trim_pitch, ahrs_trim_pitch.get())) { + _last_ahrs_trim_pitch = ahrs_trim_pitch.get(); + ahrs_view->set_pitch_trim(_last_ahrs_trim_pitch); + } + if (plane.afs.should_crash_vehicle()) { motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN); motors->output(); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 5b4c962648..91aa036b51 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -241,6 +241,7 @@ private: // Quadplane trim, degrees AP_Float ahrs_trim_pitch; + float _last_ahrs_trim_pitch; // fw landing approach radius AP_Float fw_land_approach_radius;