AP_NavEKF2: Critical bug fix - perf counter not initialised

This commit is contained in:
Paul Riseborough 2015-10-15 09:18:24 +11:00
parent 9b80ab18ae
commit e3013b493b
3 changed files with 5 additions and 4 deletions

View File

@ -98,7 +98,7 @@ The filter can fuse motion compensated optiocal flow rates and range finder meas
void NavEKF2_core::EstimateTerrainOffset() void NavEKF2_core::EstimateTerrainOffset()
{ {
// start performance timer // start performance timer
perf_begin(_perf_OpticalFlowEKF); perf_begin(_perf_TerrainOffset);
// constrain height above ground to be above range measured on ground // constrain height above ground to be above range measured on ground
float heightAboveGndEst = max((terrainState - stateStruct.position.z), rngOnGnd); float heightAboveGndEst = max((terrainState - stateStruct.position.z), rngOnGnd);
@ -271,7 +271,7 @@ void NavEKF2_core::EstimateTerrainOffset()
} }
// stop the performance timer // stop the performance timer
perf_end(_perf_OpticalFlowEKF); perf_end(_perf_TerrainOffset);
} }
/* /*

View File

@ -49,7 +49,8 @@ NavEKF2_core::NavEKF2_core(NavEKF2 &_frontend, const AP_AHRS *ahrs, AP_Baro &bar
_perf_FuseMagnetometer(perf_alloc(PC_ELAPSED, "EKF_FuseMagnetometer")), _perf_FuseMagnetometer(perf_alloc(PC_ELAPSED, "EKF_FuseMagnetometer")),
_perf_FuseAirspeed(perf_alloc(PC_ELAPSED, "EKF_FuseAirspeed")), _perf_FuseAirspeed(perf_alloc(PC_ELAPSED, "EKF_FuseAirspeed")),
_perf_FuseSideslip(perf_alloc(PC_ELAPSED, "EKF_FuseSideslip")), _perf_FuseSideslip(perf_alloc(PC_ELAPSED, "EKF_FuseSideslip")),
_perf_OpticalFlowEKF(perf_alloc(PC_ELAPSED, "EKF_FuseOptFlow")) _perf_FuseOptFlow(perf_alloc(PC_ELAPSED, "EKF_FuseOptFlow")),
_perf_TerrainOffset(perf_alloc(PC_ELAPSED, "EKF_TerrainOffset"))
#endif #endif
{ {
} }

View File

@ -882,7 +882,7 @@ private:
perf_counter_t _perf_FuseMagnetometer; perf_counter_t _perf_FuseMagnetometer;
perf_counter_t _perf_FuseAirspeed; perf_counter_t _perf_FuseAirspeed;
perf_counter_t _perf_FuseSideslip; perf_counter_t _perf_FuseSideslip;
perf_counter_t _perf_OpticalFlowEKF; perf_counter_t _perf_TerrainOffset;
perf_counter_t _perf_FuseOptFlow; perf_counter_t _perf_FuseOptFlow;
#endif #endif