From 684e32068b72d179ceb7151ce1453922befa2b59 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Jun 2021 09:59:07 +1000 Subject: [PATCH] AP_Compass: removed perf counters --- libraries/AP_Compass/AP_Compass_BMM150.cpp | 3 --- libraries/AP_Compass/AP_Compass_BMM150.h | 1 - libraries/AP_Compass/AP_Compass_IST8308.cpp | 4 ---- libraries/AP_Compass/AP_Compass_IST8308.h | 1 - libraries/AP_Compass/AP_Compass_IST8310.cpp | 6 ------ libraries/AP_Compass/AP_Compass_IST8310.h | 2 -- 6 files changed, 17 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_BMM150.cpp b/libraries/AP_Compass/AP_Compass_BMM150.cpp index d6dec88614..4202e07b7d 100644 --- a/libraries/AP_Compass/AP_Compass_BMM150.cpp +++ b/libraries/AP_Compass/AP_Compass_BMM150.cpp @@ -223,8 +223,6 @@ bool AP_Compass_BMM150::init() set_external(_compass_instance, true); } - _perf_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "BMM150_err"); - // 2 retries for run _dev->set_retries(2); @@ -298,7 +296,6 @@ void AP_Compass_BMM150::_update() _last_read_ms = now; _dev->write_register(POWER_AND_OPERATIONS_REG, SOFT_RESET); _dev->write_register(POWER_AND_OPERATIONS_REG, POWER_CONTROL_VAL, true); - hal.util->perf_count(_perf_err); } return; } diff --git a/libraries/AP_Compass/AP_Compass_BMM150.h b/libraries/AP_Compass/AP_Compass_BMM150.h index d001b10a5f..36cd26ac73 100644 --- a/libraries/AP_Compass/AP_Compass_BMM150.h +++ b/libraries/AP_Compass/AP_Compass_BMM150.h @@ -67,7 +67,6 @@ private: } _dig; uint32_t _last_read_ms; - AP_HAL::Util::perf_counter_t _perf_err; enum Rotation _rotation; bool _force_external; }; diff --git a/libraries/AP_Compass/AP_Compass_IST8308.cpp b/libraries/AP_Compass/AP_Compass_IST8308.cpp index b90958a79d..9aa883c9e8 100644 --- a/libraries/AP_Compass/AP_Compass_IST8308.cpp +++ b/libraries/AP_Compass/AP_Compass_IST8308.cpp @@ -177,8 +177,6 @@ bool AP_Compass_IST8308::init() _dev->register_periodic_callback(SAMPLING_PERIOD_USEC, FUNCTOR_BIND_MEMBER(&AP_Compass_IST8308::timer, void)); - _perf_xfer_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "IST8308_xfer_err"); - return true; fail: @@ -197,7 +195,6 @@ void AP_Compass_IST8308::timer() if (!_dev->read_registers(STAT1_REG, &stat, 1) || !(stat & STAT1_VAL_DRDY)) { - hal.util->perf_count(_perf_xfer_err); return; } @@ -207,7 +204,6 @@ void AP_Compass_IST8308::timer() if (!_dev->read_registers(DATAX_L_REG, (uint8_t *) &buffer, sizeof(buffer))) { - hal.util->perf_count(_perf_xfer_err); return; } diff --git a/libraries/AP_Compass/AP_Compass_IST8308.h b/libraries/AP_Compass/AP_Compass_IST8308.h index dd1c595065..002158247b 100644 --- a/libraries/AP_Compass/AP_Compass_IST8308.h +++ b/libraries/AP_Compass/AP_Compass_IST8308.h @@ -48,7 +48,6 @@ private: bool init(); AP_HAL::OwnPtr _dev; - AP_HAL::Util::perf_counter_t _perf_xfer_err; enum Rotation _rotation; uint8_t _instance; diff --git a/libraries/AP_Compass/AP_Compass_IST8310.cpp b/libraries/AP_Compass/AP_Compass_IST8310.cpp index 018572a539..cd4fb05cb3 100644 --- a/libraries/AP_Compass/AP_Compass_IST8310.cpp +++ b/libraries/AP_Compass/AP_Compass_IST8310.cpp @@ -171,9 +171,6 @@ bool AP_Compass_IST8310::init() _periodic_handle = _dev->register_periodic_callback(SAMPLING_PERIOD_USEC, FUNCTOR_BIND_MEMBER(&AP_Compass_IST8310::timer, void)); - _perf_xfer_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "IST8310_xfer_err"); - _perf_bad_data = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "IST8310_bad_data"); - return true; fail: @@ -184,7 +181,6 @@ fail: void AP_Compass_IST8310::start_conversion() { if (!_dev->write_register(CNTL1_REG, CNTL1_VAL_SINGLE_MEASUREMENT_MODE)) { - hal.util->perf_count(_perf_xfer_err); _ignore_next_sample = true; } } @@ -205,7 +201,6 @@ void AP_Compass_IST8310::timer() bool ret = _dev->read_registers(OUTPUT_X_L_REG, (uint8_t *) &buffer, sizeof(buffer)); if (!ret) { - hal.util->perf_count(_perf_xfer_err); return; } @@ -225,7 +220,6 @@ void AP_Compass_IST8310::timer() if (x > IST8310_MAX_VAL_XY || x < IST8310_MIN_VAL_XY || y > IST8310_MAX_VAL_XY || y < IST8310_MIN_VAL_XY || z > IST8310_MAX_VAL_Z || z < IST8310_MIN_VAL_Z) { - hal.util->perf_count(_perf_bad_data); return; } diff --git a/libraries/AP_Compass/AP_Compass_IST8310.h b/libraries/AP_Compass/AP_Compass_IST8310.h index 65073f21b4..e206c94961 100644 --- a/libraries/AP_Compass/AP_Compass_IST8310.h +++ b/libraries/AP_Compass/AP_Compass_IST8310.h @@ -50,8 +50,6 @@ private: AP_HAL::OwnPtr _dev; AP_HAL::Device::PeriodicHandle _periodic_handle; - AP_HAL::Util::perf_counter_t _perf_xfer_err; - AP_HAL::Util::perf_counter_t _perf_bad_data; enum Rotation _rotation; uint8_t _instance;