Browse Source

Plane: quadplane: remvoe unused loiter initial pitch varable

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
abe9e4425b
  1. 3
      ArduPlane/mode_qloiter.cpp
  2. 3
      ArduPlane/quadplane.h

3
ArduPlane/mode_qloiter.cpp

@ -15,9 +15,6 @@ bool ModeQLoiter::_enter()
quadplane.init_throttle_wait(); quadplane.init_throttle_wait();
// remember initial pitch
quadplane.loiter_initial_pitch_cd = MAX(plane.ahrs.pitch_sensor, 0);
// prevent re-init of target position // prevent re-init of target position
quadplane.last_loiter_ms = AP_HAL::millis(); quadplane.last_loiter_ms = AP_HAL::millis();
return true; return true;

3
ArduPlane/quadplane.h

@ -374,9 +374,6 @@ private:
Location last_auto_target; Location last_auto_target;
// pitch when we enter loiter mode
int32_t loiter_initial_pitch_cd;
// when did we last run the attitude controller? // when did we last run the attitude controller?
uint32_t last_att_control_ms; uint32_t last_att_control_ms;

Loading…
Cancel
Save