PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Performance measuring tools. More...
#include <stdint.h>
#include <px4_platform_common/defines.h>
Go to the source code of this file.
Macros | |
#define | _SYSTEMLIB_PERF_COUNTER_H value |
#define | LATENCY_BUCKET_COUNT 8 |
Typedefs | |
typedef struct perf_ctr_header * | perf_counter_t |
typedef void(* | perf_callback) (perf_counter_t handle, void *user) |
Enumerations | |
enum | perf_counter_type { PC_COUNT, PC_ELAPSED, PC_INTERVAL } |
Counter types. More... | |
Functions | |
__BEGIN_DECLS __EXPORT perf_counter_t | perf_alloc (enum perf_counter_type type, const char *name) |
Create a new local counter. More... | |
__EXPORT perf_counter_t | perf_alloc_once (enum perf_counter_type type, const char *name) |
Get the reference to an existing counter or create a new one if it does not exist. More... | |
__EXPORT void | perf_free (perf_counter_t handle) |
Free a counter. More... | |
__EXPORT void | perf_count (perf_counter_t handle) |
Count a performance event. More... | |
__EXPORT void | perf_begin (perf_counter_t handle) |
Begin a performance event. More... | |
__EXPORT void | perf_end (perf_counter_t handle) |
End a performance event. More... | |
__EXPORT void | perf_set_elapsed (perf_counter_t handle, int64_t elapsed) |
Register a measurement. More... | |
__EXPORT void | perf_set_count (perf_counter_t handle, uint64_t count) |
Set a counter. More... | |
__EXPORT void | perf_cancel (perf_counter_t handle) |
Cancel a performance event. More... | |
__EXPORT void | perf_reset (perf_counter_t handle) |
Reset a performance counter. More... | |
__EXPORT void | perf_print_counter (perf_counter_t handle) |
Print one performance counter to stdout. More... | |
__EXPORT void | perf_print_counter_fd (int fd, perf_counter_t handle) |
Print one performance counter to a fd. More... | |
__EXPORT int | perf_print_counter_buffer (char *buffer, int length, perf_counter_t handle) |
Print one performance counter to a buffer. More... | |
__EXPORT void | perf_print_all (int fd) |
Print all of the performance counters. More... | |
__EXPORT void | perf_iterate_all (perf_callback cb, void *user) |
Iterate over all performance counters using a callback. More... | |
__EXPORT void | perf_print_latency (int fd) |
Print hrt latency counters. More... | |
__EXPORT void | perf_reset_all (void) |
Reset all of the performance counters. More... | |
__EXPORT uint64_t | perf_event_count (perf_counter_t handle) |
Return current event_count. More... | |
Variables | |
const uint16_t | latency_bucket_count |
const uint16_t | latency_buckets [LATENCY_BUCKET_COUNT] |
uint32_t | latency_counters [LATENCY_BUCKET_COUNT+1] |
Performance measuring tools.
Definition in file perf_counter.h.
#define _SYSTEMLIB_PERF_COUNTER_H value |
Definition at line 40 of file perf_counter.h.
#define LATENCY_BUCKET_COUNT 8 |
Definition at line 45 of file perf_counter.h.
typedef void(* perf_callback) (perf_counter_t handle, void *user) |
Definition at line 197 of file perf_counter.h.
typedef struct perf_ctr_header* perf_counter_t |
Definition at line 61 of file perf_counter.h.
enum perf_counter_type |
Counter types.
Enumerator | |
---|---|
PC_COUNT | count the number of times an event occurs |
PC_ELAPSED | measure the time elapsed performing an event |
PC_INTERVAL | measure the interval between instances of an event |
Definition at line 54 of file perf_counter.h.
__BEGIN_DECLS __EXPORT perf_counter_t perf_alloc | ( | enum perf_counter_type | type, |
const char * | name | ||
) |
Create a new local counter.
type | The type of the new counter. |
name | The counter name. |
Definition at line 123 of file perf_counter.cpp.
References perf_ctr_header::link, perf_ctr_header::name, PC_COUNT, PC_ELAPSED, PC_INTERVAL, perf_counters, perf_counters_mutex, and perf_ctr_header::type.
Referenced by perf_alloc_once().
__EXPORT perf_counter_t perf_alloc_once | ( | enum perf_counter_type | type, |
const char * | name | ||
) |
Get the reference to an existing counter or create a new one if it does not exist.
type | The type of the counter. |
name | The counter name. |
Definition at line 156 of file perf_counter.cpp.
References perf_ctr_header::link, perf_ctr_header::name, perf_alloc(), perf_counters, perf_counters_mutex, and perf_ctr_header::type.
Referenced by AirspeedModule::AirspeedModule().
__EXPORT void perf_begin | ( | perf_counter_t | handle | ) |
Begin a performance event.
This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
handle | The handle returned from perf_alloc. |
Definition at line 258 of file perf_counter.cpp.
References hrt_absolute_time(), PC_ELAPSED, and perf_ctr_header::type.
Referenced by DfMS5607Wrapper::_publish(), DfMS5611Wrapper::_publish(), DfBmp280Wrapper::_publish(), DfAK8963Wrapper::_publish(), DfHmc5883Wrapper::_publish(), DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), load_mon::LoadMon::_ram_used(), adc_measure(), at24c_bread(), at24c_bwrite(), at24c_initialize(), BMP280::collect(), MS5525::collect(), TFMINI::collect(), ETSAirspeed::collect(), SDP3X::collect(), MEASAirspeed::collect(), SRF02::collect(), TERARANGER::collect(), CM8JL65::collect(), VL53LXX::collect(), LidarLiteI2C::collect(), Radar::collect(), MB12XX::collect(), MPL3115A2::collect(), SF1XX::collect(), LeddarOne::collect(), PX4FLOW::collect(), SF0X::collect(), LSM303AGR::collect(), MS5611::collect(), LPS22HB::collect(), RM3100::collect(), MappyDot::collect(), LIS3MDL::collect(), INA226::collect(), LPS25H::collect(), QMC5883::collect(), HMC5883::collect(), BMM150::collect(), IST8310::collect(), BMP388::collect(), controls_tick(), RCInput::cycle(), dm_read(), dm_write(), dsm_port_input(), px4::logger::LogWriterFile::LogFileBuffer::fsync(), BMP280::measure(), LidarLitePWM::measure(), ADIS16477::measure(), FXAS21002C::measure(), MPL3115A2::measure(), ADIS16448::measure(), ADIS16497::measure(), VOXLPM::measure(), MS5611::measure(), BMA180::measure(), BMI055_gyro::measure(), BMI055_accel::measure(), BMI088_gyro::measure(), BMI088_accel::measure(), L3GD20::measure(), BMM150::measure(), MPU9250::measure(), BMI160::measure(), BMP388::measure(), MPU6000::measure(), ICM20948::measure(), LSM303D::measureAccelerometer(), LSM303D::measureMagnetometer(), param_export(), param_find_internal(), param_get(), param_save_default(), param_set_internal(), Sih::run(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), RCUpdate::RCUpdate::Run(), AirspeedModule::Run(), FixedwingAttitudeControl::Run(), MulticopterPositionControl::Run(), RoverPositionControl::run(), VtolAttitudeControl::Run(), Sensors::run(), PAW3902::Run(), Ekf2::Run(), Navigator::run(), BatteryStatus::Run(), DShotOutput::Run(), FXOS8701CQ::Run(), PX4FMU::Run(), PMW3901::Run(), FixedwingPositionControl::Run(), UavcanNode::Run(), land_detector::LandDetector::Run(), rx_dma_callback(), ADC::sample(), PX4IO::task_main(), Mavlink::task_main(), test_perf(), user_start(), PX4IO::write(), and px4::logger::LogWriterFile::LogFileBuffer::write_to_file().
__EXPORT void perf_cancel | ( | perf_counter_t | handle | ) |
Cancel a performance event.
This call applies to counters that operate over ranges of time; PC_ELAPSED etc. It reverts the effect of a previous perf_begin.
handle | The handle returned from perf_alloc. |
Definition at line 380 of file perf_counter.cpp.
References PC_ELAPSED, perf_ctr_elapsed::time_start, and perf_ctr_header::type.
Referenced by BMP280::collect(), BMP388::collect(), BMP280::measure(), BMM150::measure(), and BMP388::measure().
__EXPORT void perf_count | ( | perf_counter_t | handle | ) |
Count a performance event.
This call only affects counters that take single events; PC_COUNT, PC_INTERVAL etc.
handle | The handle returned from perf_alloc. |
Definition at line 199 of file perf_counter.cpp.
References dt, perf_ctr_interval::event_count, hrt_absolute_time(), hrt_abstime, perf_ctr_interval::M2, perf_ctr_interval::mean, PC_COUNT, PC_INTERVAL, perf_ctr_interval::time_first, perf_ctr_interval::time_last, perf_ctr_interval::time_least, perf_ctr_interval::time_most, and perf_ctr_header::type.
Referenced by at24c_bread(), at24c_bwrite(), QMC5883::check_conf(), HMC5883::check_conf(), IST8310::check_conf(), MPU9250::check_duplicate(), ICM20948::check_duplicate(), MPU9250::check_null_data(), ICM20948::check_null_data(), HMC5883::check_range(), FXAS21002C::check_registers(), FXOS8701CQ::check_registers(), LSM303D::check_registers(), BMI055_gyro::check_registers(), BMI055_accel::check_registers(), BMI088_gyro::check_registers(), L3GD20::check_registers(), BMI088_accel::check_registers(), BMI160::check_registers(), MPU9250::check_registers(), MPU6000::check_registers(), ICM20948::check_registers(), BMP280::collect(), MS5525::collect(), TFMINI::collect(), ETSAirspeed::collect(), SDP3X::collect(), MEASAirspeed::collect(), SRF02::collect(), TERARANGER::collect(), CM8JL65::collect(), VL53LXX::collect(), LidarLiteI2C::collect(), MB12XX::collect(), MPL3115A2::collect(), SF1XX::collect(), LeddarOne::collect(), PX4FLOW::collect(), SF0X::collect(), MS5611::collect(), LPS22HB::collect(), RM3100::collect(), MappyDot::collect(), LIS3MDL::collect(), INA226::collect(), LPS25H::collect(), QMC5883::collect(), HMC5883::collect(), BMM150::collect(), IST8310::collect(), BMP388::collect(), RCInput::cycle(), hott_telemetry_thread_main(), MS5525::init_ms5525(), SDP3X::init_sdp3x(), AK09916::is_ready(), BMP280::measure(), MS5525::measure(), LidarLitePWM::measure(), ETSAirspeed::measure(), MEASAirspeed::measure(), AK09916::measure(), LidarLiteI2C::measure(), ADIS16477::measure(), SRF02::measure(), TERARANGER::measure(), VL53LXX::measure(), FXAS21002C::measure(), ICM20948_mag::measure(), MPL3115A2::measure(), MPU9250_mag::measure(), ADIS16448::measure(), SF1XX::measure(), PX4FLOW::measure(), SF0X::measure(), ADIS16497::measure(), MS5611::measure(), LPS22HB::measure(), BMI055_gyro::measure(), BMI055_accel::measure(), BMI088_gyro::measure(), INA226::measure(), RM3100::measure(), BMI088_accel::measure(), LIS3MDL::measure(), LPS25H::measure(), L3GD20::measure(), HMC5883::measure(), BMM150::measure(), BMI160::measure(), IST8310::measure(), BMP388::measure(), MPU6000::measure(), ICM20948::measure(), LSM303D::measureAccelerometer(), INA226::probe(), PX4IO_serial_interface(), INA226::read(), PCA9685::read8(), PMW3901::readMotionCount(), VL53LXX::readRegister(), PMW3901::readRegister(), VL53LXX::readRegisterMulti(), recv_req_id(), MPU6000::reset(), ETSAirspeed::Run(), PAW3902::Run(), FXOS8701CQ::Run(), UavcanNode::Run(), rx_handle_packet(), serial_interrupt(), HMC5883::set_excitement(), LIS3MDL::set_excitement(), HMC5883::set_range(), LIS3MDL::set_range(), IST8310::set_selftest(), HMC5883::set_temperature_compensation(), PCA9685::setPWM(), Mavlink::task_main(), test_perf(), user_start(), PCA9685::write8(), VL53LXX::writeRegister(), PMW3901::writeRegister(), and VL53LXX::writeRegisterMulti().
__EXPORT void perf_end | ( | perf_counter_t | handle | ) |
End a performance event.
This call applies to counters that operate over ranges of time; PC_ELAPSED etc. If a call is made without a corresponding perf_begin call, or if perf_cancel has been called subsequently, no change is made to the counter.
handle | The handle returned from perf_alloc. |
Definition at line 275 of file perf_counter.cpp.
References dt, perf_ctr_elapsed::event_count, hrt_absolute_time(), perf_ctr_elapsed::M2, perf_ctr_elapsed::mean, PC_ELAPSED, perf_ctr_elapsed::time_least, perf_ctr_elapsed::time_most, perf_ctr_elapsed::time_start, perf_ctr_elapsed::time_total, and perf_ctr_header::type.
Referenced by DfMS5607Wrapper::_publish(), DfMS5611Wrapper::_publish(), DfBmp280Wrapper::_publish(), DfAK8963Wrapper::_publish(), DfHmc5883Wrapper::_publish(), DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), load_mon::LoadMon::_ram_used(), adc_measure(), at24c_bread(), at24c_bwrite(), at24c_initialize(), MPU9250::check_duplicate(), ICM20948::check_duplicate(), MPU9250::check_null_data(), ICM20948::check_null_data(), BMP280::collect(), MS5525::collect(), TFMINI::collect(), ETSAirspeed::collect(), SDP3X::collect(), MEASAirspeed::collect(), SRF02::collect(), TERARANGER::collect(), CM8JL65::collect(), VL53LXX::collect(), LidarLiteI2C::collect(), Radar::collect(), MB12XX::collect(), MPL3115A2::collect(), SF1XX::collect(), LeddarOne::collect(), PX4FLOW::collect(), SF0X::collect(), LSM303AGR::collect(), MS5611::collect(), LPS22HB::collect(), RM3100::collect(), MappyDot::collect(), LIS3MDL::collect(), INA226::collect(), QMC5883::collect(), LPS25H::collect(), HMC5883::collect(), BMM150::collect(), IST8310::collect(), BMP388::collect(), controls_tick(), RCInput::cycle(), dm_read(), dm_write(), dsm_port_input(), px4::logger::LogWriterFile::LogFileBuffer::fsync(), BMP280::measure(), LidarLitePWM::measure(), ADIS16477::measure(), FXAS21002C::measure(), MPL3115A2::measure(), ADIS16448::measure(), ADIS16497::measure(), VOXLPM::measure(), MS5611::measure(), BMA180::measure(), BMI055_gyro::measure(), BMI055_accel::measure(), BMI088_gyro::measure(), BMI088_accel::measure(), L3GD20::measure(), BMM150::measure(), MPU9250::measure(), BMI160::measure(), BMP388::measure(), MPU6000::measure(), ICM20948::measure(), LSM303D::measureAccelerometer(), LSM303D::measureMagnetometer(), param_export(), param_find_internal(), param_get(), param_save_default(), param_set_internal(), Sih::run(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), RCUpdate::RCUpdate::Run(), AirspeedModule::Run(), FixedwingAttitudeControl::Run(), RoverPositionControl::run(), MulticopterPositionControl::Run(), VtolAttitudeControl::Run(), PAW3902::Run(), Sensors::run(), Ekf2::Run(), Navigator::run(), BatteryStatus::Run(), DShotOutput::Run(), FXOS8701CQ::Run(), PX4FMU::Run(), PMW3901::Run(), FixedwingPositionControl::Run(), UavcanNode::Run(), land_detector::LandDetector::Run(), rx_dma_callback(), ADC::sample(), PX4IO::task_main(), Mavlink::task_main(), test_perf(), user_start(), PX4IO::write(), and px4::logger::LogWriterFile::LogFileBuffer::write_to_file().
__EXPORT uint64_t perf_event_count | ( | perf_counter_t | handle | ) |
Return current event_count.
handle | The counter returned from perf_alloc. |
Definition at line 547 of file perf_counter.cpp.
References perf_ctr_elapsed::event_count, perf_ctr_interval::event_count, PC_COUNT, PC_ELAPSED, PC_INTERVAL, and perf_ctr_header::type.
Referenced by BMP280::collect(), MS5525::collect(), ETSAirspeed::collect(), SDP3X::collect(), MEASAirspeed::collect(), LidarLiteI2C::collect(), MPL3115A2::collect(), LSM303AGR::collect(), MS5611::collect(), LPS22HB::collect(), RM3100::collect(), LIS3MDL::collect(), LPS25H::collect(), QMC5883::collect(), HMC5883::collect(), BMM150::collect(), IST8310::collect(), BMP388::collect(), AK09916::measure(), LidarLiteI2C::measure(), FXAS21002C::measure(), ICM20948_mag::measure(), ADIS16448::measure(), MPU9250_mag::measure(), ADIS16497::measure(), BMI055_gyro::measure(), BMI055_accel::measure(), BMI088_gyro::measure(), BMI088_accel::measure(), L3GD20::measure(), MPU9250::measure(), BMI160::measure(), MPU6000::measure(), ICM20948::measure(), LSM303D::measureAccelerometer(), LSM303D::measureMagnetometer(), FXOS8701CQ::Run(), and BMM150::self_test().
__EXPORT void perf_free | ( | perf_counter_t | handle | ) |
Free a counter.
handle | The performance counter's handle. |
Definition at line 185 of file perf_counter.cpp.
References perf_ctr_header::link, perf_counters, and perf_counters_mutex.
Referenced by hott_telemetry_thread_main(), PX4IO_serial_interface(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), task_main(), test_perf(), ADC::~ADC(), ADIS16448::~ADIS16448(), ADIS16477::~ADIS16477(), ADIS16497::~ADIS16497(), Airspeed::~Airspeed(), AirspeedModule::~AirspeedModule(), AK09916::~AK09916(), BATT_SMBUS::~BATT_SMBUS(), BMA180::~BMA180(), BMI055_accel::~BMI055_accel(), BMI055_gyro::~BMI055_gyro(), BMI088_accel::~BMI088_accel(), BMI088_gyro::~BMI088_gyro(), BMI160::~BMI160(), BMM150::~BMM150(), BMP280::~BMP280(), BMP388::~BMP388(), CM8JL65::~CM8JL65(), DfAK8963Wrapper::~DfAK8963Wrapper(), DfBmp280Wrapper::~DfBmp280Wrapper(), DfHmc5883Wrapper::~DfHmc5883Wrapper(), DfLsm9ds1Wrapper::~DfLsm9ds1Wrapper(), DfMPU6050Wrapper::~DfMPU6050Wrapper(), DfMpu9250Wrapper::~DfMpu9250Wrapper(), DfMS5607Wrapper::~DfMS5607Wrapper(), DfMS5611Wrapper::~DfMS5611Wrapper(), DShotOutput::~DShotOutput(), Ekf2::~Ekf2(), FixedwingAttitudeControl::~FixedwingAttitudeControl(), FixedwingPositionControl::~FixedwingPositionControl(), FXAS21002C::~FXAS21002C(), FXOS8701CQ::~FXOS8701CQ(), HMC5883::~HMC5883(), ICM20948::~ICM20948(), ICM20948_mag::~ICM20948_mag(), INA226::~INA226(), IST8310::~IST8310(), L3GD20::~L3GD20(), land_detector::LandDetector::~LandDetector(), LeddarOne::~LeddarOne(), LidarLite::~LidarLite(), LIS3MDL::~LIS3MDL(), load_mon::LoadMon::~LoadMon(), px4::logger::LogWriterFile::LogFileBuffer::~LogFileBuffer(), LPS22HB::~LPS22HB(), LPS25H::~LPS25H(), LSM303AGR::~LSM303AGR(), LSM303D::~LSM303D(), MappyDot::~MappyDot(), Mavlink::~Mavlink(), MB12XX::~MB12XX(), MixingOutput::~MixingOutput(), MPL3115A2::~MPL3115A2(), MPU6000::~MPU6000(), MPU9250::~MPU9250(), MPU9250_mag::~MPU9250_mag(), MS5611::~MS5611(), MulticopterAttitudeControl::~MulticopterAttitudeControl(), MulticopterPositionControl::~MulticopterPositionControl(), MulticopterRateControl::~MulticopterRateControl(), PAW3902::~PAW3902(), PMW3901::~PMW3901(), PX4FLOW::~PX4FLOW(), PX4FMU::~PX4FMU(), PX4IO::~PX4IO(), QMC5883::~QMC5883(), Radar::~Radar(), RCInput::~RCInput(), RCUpdate::RCUpdate::~RCUpdate(), RM3100::~RM3100(), RoverPositionControl::~RoverPositionControl(), SF0X::~SF0X(), SF1XX::~SF1XX(), Simulator::~Simulator(), SRF02::~SRF02(), TAP_ESC::~TAP_ESC(), TERARANGER::~TERARANGER(), TFMINI::~TFMINI(), UavcanNode::~UavcanNode(), VL53LXX::~VL53LXX(), VOXLPM::~VOXLPM(), and VtolAttitudeControl::~VtolAttitudeControl().
__EXPORT void perf_iterate_all | ( | perf_callback | cb, |
void * | user | ||
) |
Iterate over all performance counters using a callback.
Caution: This will aquire the mutex, so do not call any other perf_* method that aquire the mutex as well from the callback (If this is needed, configure the mutex to be reentrant).
cb | callback method |
user | custom argument for the callback |
Definition at line 575 of file perf_counter.cpp.
References perf_ctr_header::link, perf_counters, and perf_counters_mutex.
Referenced by px4::logger::Logger::write_perf_data().
__EXPORT void perf_print_all | ( | int | fd | ) |
Print all of the performance counters.
fd | File descriptor to print to - e.g. 0 for stdout |
Definition at line 589 of file perf_counter.cpp.
References perf_ctr_header::link, perf_counters, perf_counters_mutex, and perf_print_counter_fd().
Referenced by perf_main(), and test_perf().
__EXPORT void perf_print_counter | ( | perf_counter_t | handle | ) |
Print one performance counter to stdout.
handle | The counter to print. |
Definition at line 437 of file perf_counter.cpp.
References perf_print_counter_fd().
Referenced by hott_telemetry_main(), DfMPU6050Wrapper::info(), DfLsm9ds1Wrapper::info(), DfMpu9250Wrapper::info(), param_print_status(), BMP280::print_info(), ADIS16477::print_info(), FXAS21002C::print_info(), TFMINI::print_info(), LidarLite::print_info(), MPL3115A2::print_info(), PX4FLOW::print_info(), AK09916::print_info(), SF0X::print_info(), ADIS16497::print_info(), TERARANGER::print_info(), PAW3902::print_info(), LPS22HB::print_info(), CM8JL65::print_info(), SF1XX::print_info(), PMW3901::print_info(), VL53LXX::print_info(), MB12XX::print_info(), SRF02::print_info(), LSM303AGR::print_info(), MS5611::print_info(), ADIS16448::print_info(), LeddarOne::print_info(), FXOS8701CQ::print_info(), Radar::print_info(), LIS3MDL::print_info(), HMC5883::print_info(), RM3100::print_info(), BMA180::print_info(), BMI088_gyro::print_info(), UavcanNode::print_info(), BMI055_gyro::print_info(), VOXLPM::print_info(), LSM303D::print_info(), BMI055_accel::print_info(), QMC5883::print_info(), INA226::print_info(), MappyDot::print_info(), LPS25H::print_info(), BMI088_accel::print_info(), L3GD20::print_info(), IST8310::print_info(), BMM150::print_info(), MPU9250::print_info(), BMI160::print_info(), MPU6000::print_info(), BMP388::print_info(), ICM20948::print_info(), MulticopterRateControl::print_status(), MulticopterAttitudeControl::print_status(), load_mon::LoadMon::print_status(), RCUpdate::RCUpdate::print_status(), FixedwingAttitudeControl::print_status(), RCInput::print_status(), AirspeedModule::print_status(), MulticopterPositionControl::print_status(), VtolAttitudeControl::print_status(), Ekf2::print_status(), DShotOutput::print_status(), PX4FMU::print_status(), FixedwingPositionControl::print_status(), MixingOutput::printStatus(), status(), and test_perf().
__EXPORT int perf_print_counter_buffer | ( | char * | buffer, |
int | length, | ||
perf_counter_t | handle | ||
) |
Print one performance counter to a buffer.
buffer | buffer to write to |
length | buffer length |
handle | The counter to print. |
return | number of bytes written |
Definition at line 495 of file perf_counter.cpp.
References perf_ctr_elapsed::event_count, perf_ctr_interval::event_count, perf_ctr_elapsed::M2, perf_ctr_interval::M2, perf_ctr_header::name, PC_COUNT, PC_ELAPSED, PC_INTERVAL, perf_ctr_interval::time_first, perf_ctr_interval::time_last, perf_ctr_elapsed::time_least, perf_ctr_interval::time_least, perf_ctr_elapsed::time_most, perf_ctr_interval::time_most, perf_ctr_elapsed::time_total, and perf_ctr_header::type.
Referenced by px4::logger::Logger::perf_iterate_callback().
__EXPORT void perf_print_counter_fd | ( | int | fd, |
perf_counter_t | handle | ||
) |
Print one performance counter to a fd.
fd | File descriptor to print to - e.g. 0 for stdout |
handle | The counter to print. |
Definition at line 447 of file perf_counter.cpp.
References perf_ctr_elapsed::event_count, perf_ctr_interval::event_count, perf_ctr_elapsed::M2, perf_ctr_interval::M2, perf_ctr_header::name, PC_COUNT, PC_ELAPSED, PC_INTERVAL, perf_ctr_interval::time_first, perf_ctr_interval::time_last, perf_ctr_elapsed::time_least, perf_ctr_interval::time_least, perf_ctr_elapsed::time_most, perf_ctr_interval::time_most, perf_ctr_elapsed::time_total, and perf_ctr_header::type.
Referenced by perf_print_all(), and perf_print_counter().
__EXPORT void perf_print_latency | ( | int | fd | ) |
Print hrt latency counters.
fd | File descriptor to print to - e.g. 0 for stdout |
Definition at line 603 of file perf_counter.cpp.
References latency_bucket_count, latency_buckets, and latency_counters.
Referenced by perf_main().
__EXPORT void perf_reset | ( | perf_counter_t | handle | ) |
Reset a performance counter.
This call resets performance counter to initial state
handle | The handle returned from perf_alloc. |
Definition at line 402 of file perf_counter.cpp.
References perf_ctr_elapsed::event_count, perf_ctr_interval::event_count, PC_COUNT, PC_ELAPSED, PC_INTERVAL, perf_ctr_interval::time_event, perf_ctr_interval::time_first, perf_ctr_interval::time_last, perf_ctr_elapsed::time_least, perf_ctr_interval::time_least, perf_ctr_elapsed::time_most, perf_ctr_interval::time_most, perf_ctr_elapsed::time_start, perf_ctr_elapsed::time_total, and perf_ctr_header::type.
Referenced by hott_telemetry_thread_main(), and perf_reset_all().
__EXPORT void perf_reset_all | ( | void | ) |
Reset all of the performance counters.
Definition at line 616 of file perf_counter.cpp.
References latency_bucket_count, latency_counters, perf_ctr_header::link, perf_counters, perf_counters_mutex, and perf_reset().
Referenced by perf_main(), and px4::logger::Logger::start_log_file().
__EXPORT void perf_set_count | ( | perf_counter_t | handle, |
uint64_t | count | ||
) |
Set a counter.
This call applies to counters of type PC_COUNT. It (re-)sets the count.
handle | The handle returned from perf_alloc. |
count | The counter value to be set. |
Definition at line 361 of file perf_counter.cpp.
References PC_COUNT, and perf_ctr_header::type.
Referenced by DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), and DfMpu9250Wrapper::_publish().
__EXPORT void perf_set_elapsed | ( | perf_counter_t | handle, |
int64_t | elapsed | ||
) |
Register a measurement.
This call applies to counters that operate over ranges of time; PC_ELAPSED etc. If a call is made without a corresponding perf_begin call. It sets the value provided as argument as a new measurement.
handle | The handle returned from perf_alloc. |
elapsed | The time elapsed. Negative values lead to incrementing the overrun counter. |
Definition at line 320 of file perf_counter.cpp.
References dt, perf_ctr_elapsed::event_count, perf_ctr_elapsed::M2, perf_ctr_elapsed::mean, PC_ELAPSED, perf_ctr_elapsed::time_least, perf_ctr_elapsed::time_most, perf_ctr_elapsed::time_start, perf_ctr_elapsed::time_total, and perf_ctr_header::type.
Referenced by TAP_ESC::cycle(), PX4IO::io_set_control_state(), linux_pwm_out::task_main(), snapdragon_pwm::task_main(), and MixingOutput::updateLatencyPerfCounter().
const uint16_t latency_bucket_count |
Definition at line 52 of file perf_counter.cpp.
Referenced by perf_print_latency(), and perf_reset_all().
const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] |
Definition at line 53 of file perf_counter.cpp.
Referenced by perf_print_latency().
uint32_t latency_counters[LATENCY_BUCKET_COUNT+1] |
Definition at line 54 of file perf_counter.cpp.
Referenced by perf_print_latency(), and perf_reset_all().