Plane: quadplane: remvoe unused loiter initial pitch varable

This commit is contained in:
Iampete1 2021-12-30 12:23:08 +00:00 committed by Andrew Tridgell
parent 7c8794b0bd
commit abe9e4425b
2 changed files with 0 additions and 6 deletions

View File

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

View File

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