forked from Archive/PX4-Autopilot
perf: added perf_event_count() method
this allows drivers to get an event_count from a perf counter
This commit is contained in:
parent
0b7294a26e
commit
7257642371
|
@ -321,6 +321,32 @@ perf_print_counter(perf_counter_t handle)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint64_t
|
||||||
|
perf_event_count(perf_counter_t handle)
|
||||||
|
{
|
||||||
|
if (handle == NULL)
|
||||||
|
return 0;
|
||||||
|
|
||||||
|
switch (handle->type) {
|
||||||
|
case PC_COUNT:
|
||||||
|
return ((struct perf_ctr_count *)handle)->event_count;
|
||||||
|
|
||||||
|
case PC_ELAPSED: {
|
||||||
|
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
|
||||||
|
return pce->event_count;
|
||||||
|
}
|
||||||
|
|
||||||
|
case PC_INTERVAL: {
|
||||||
|
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
|
||||||
|
return pci->event_count;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
perf_print_all(void)
|
perf_print_all(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -135,6 +135,14 @@ __EXPORT extern void perf_print_all(void);
|
||||||
*/
|
*/
|
||||||
__EXPORT extern void perf_reset_all(void);
|
__EXPORT extern void perf_reset_all(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return current event_count
|
||||||
|
*
|
||||||
|
* @param handle The counter returned from perf_alloc.
|
||||||
|
* @return event_count
|
||||||
|
*/
|
||||||
|
__EXPORT extern uint64_t perf_event_count(perf_counter_t handle);
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue