Browse Source

AC_Autorotation: use accel_to_angle()

gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
ecbcbbe044
  1. 2
      libraries/AC_Autorotation/AC_Autorotation.cpp

2
libraries/AC_Autorotation/AC_Autorotation.cpp

@ -366,7 +366,7 @@ void AC_Autorotation::update_forward_speed_controller(void) @@ -366,7 +366,7 @@ void AC_Autorotation::update_forward_speed_controller(void)
_accel_out_last = _accel_out;
// update angle targets that will be passed to stabilize controller
_pitch_target = atanf(-_accel_out/(GRAVITY_MSS * 100.0f))*(18000.0f/M_PI);
_pitch_target = accel_to_angle(-_accel_out*0.01) * 100;
}

Loading…
Cancel
Save