mirror of https://github.com/ArduPilot/ardupilot
Plane: allow changing Q_TRIM_PITCH in flight
change float comparison to is_equal
This commit is contained in:
parent
0e2e077d96
commit
b9f3118374
|
@ -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();
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue