diff --git a/ArduPlane/mode_qloiter.cpp b/ArduPlane/mode_qloiter.cpp index 3a43f3670a..836143192e 100644 --- a/ArduPlane/mode_qloiter.cpp +++ b/ArduPlane/mode_qloiter.cpp @@ -15,9 +15,6 @@ bool ModeQLoiter::_enter() quadplane.init_throttle_wait(); - // remember initial pitch - quadplane.loiter_initial_pitch_cd = MAX(plane.ahrs.pitch_sensor, 0); - // prevent re-init of target position quadplane.last_loiter_ms = AP_HAL::millis(); return true; diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index de58ae3766..5d9b670731 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -374,9 +374,6 @@ private: Location last_auto_target; - // pitch when we enter loiter mode - int32_t loiter_initial_pitch_cd; - // when did we last run the attitude controller? uint32_t last_att_control_ms;