Copter: Expand EKF speed limit public method to handle control limits

This commit is contained in:
priseborough 2014-11-16 12:42:56 +11:00 committed by Andrew Tridgell
parent 5b8265ad6f
commit 9e7709fa09
2 changed files with 3 additions and 1 deletions

View File

@ -321,6 +321,8 @@ static AP_OpticalFlow_PX4 optflow(ahrs);
#endif #endif
// gnd speed limit required to observe optical flow sensor limits // gnd speed limit required to observe optical flow sensor limits
static float ekfGndSpdLimit; static float ekfGndSpdLimit;
// scale factor applied to velocity controller gain to prevent optical flow noise causing excessive angle demand noise
static float ekfNavVelGainScaler;
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// GCS selection // GCS selection

View File

@ -121,7 +121,7 @@ static bool set_mode(uint8_t mode)
static void update_flight_mode() static void update_flight_mode()
{ {
// Update EKF speed limit - used to limit speed when we are using optical flow // Update EKF speed limit - used to limit speed when we are using optical flow
ekfGndSpdLimit = ahrs.getSpeedLimit(); ahrs.getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
switch (control_mode) { switch (control_mode) {
case ACRO: case ACRO:
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME