mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
AP_Compass: removed perf counters
This commit is contained in:
parent
d6348a0786
commit
684e32068b
@ -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;
|
||||
}
|
||||
|
@ -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;
|
||||
};
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
@ -48,7 +48,6 @@ private:
|
||||
bool init();
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
||||
AP_HAL::Util::perf_counter_t _perf_xfer_err;
|
||||
|
||||
enum Rotation _rotation;
|
||||
uint8_t _instance;
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
@ -50,8 +50,6 @@ private:
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> _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;
|
||||
|
Loading…
Reference in New Issue
Block a user