Plane: allow changing Q_TRIM_PITCH in flight

change float comparison to is_equal
This commit is contained in:
Mark Whitehorn 2019-02-04 10:14:01 -07:00 committed by Andrew Tridgell
parent 0e2e077d96
commit b9f3118374
2 changed files with 8 additions and 2 deletions

View File

@ -1459,6 +1459,11 @@ void QuadPlane::update(void)
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();

View File

@ -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;