Browse Source

AP_NavEKF_core: fix init of perf

_perf_FuseOptFlow  was used and not allocated
mission-4.1.18
Julien BERAUD 9 years ago committed by Andrew Tridgell
parent
commit
259f5f07e8
  1. 3
      libraries/AP_NavEKF/AP_NavEKF_core.cpp

3
libraries/AP_NavEKF/AP_NavEKF_core.cpp

@ -4373,7 +4373,8 @@ void NavEKF_core::InitialiseVariables()
_perf_FuseMagnetometer = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_FuseMagnetometer"); _perf_FuseMagnetometer = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_FuseMagnetometer");
_perf_FuseAirspeed = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_FuseAirspeed"); _perf_FuseAirspeed = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_FuseAirspeed");
_perf_FuseSideslip = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_FuseSideslip"); _perf_FuseSideslip = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_FuseSideslip");
_perf_OpticalFlowEKF = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_FuseOptFlow"); _perf_OpticalFlowEKF = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_OpticalFlowEKF");
_perf_FuseOptFlow = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EKF_FuseOptFlow");
} }
// initialise time stamps // initialise time stamps

Loading…
Cancel
Save