AP_HAL_Linux: Perf: make lttng use internal fields

Instead of creating a new object Perf_Lttng copying the necessaries
fields, just make a tighter integration with the internal perf counters
and re-use the same fields.
This commit is contained in:
Lucas De Marchi 2016-05-24 10:26:26 -03:00
parent 619ce23799
commit 1727418dc9
5 changed files with 25 additions and 40 deletions

View File

@ -86,9 +86,7 @@ void Perf::begin(Util::perf_counter_t pc)
perf.start = now_nsec(); perf.start = now_nsec();
#ifdef HAVE_LTTNG_UST perf.lttng.begin(perf.name);
perf.lttng.begin();
#endif
} }
void Perf::end(Util::perf_counter_t pc) void Perf::end(Util::perf_counter_t pc)
@ -137,9 +135,7 @@ void Perf::end(Util::perf_counter_t pc)
perf.m2 += (delta_intvl * (elapsed - perf.mean)); perf.m2 += (delta_intvl * (elapsed - perf.mean));
perf.start = 0; perf.start = 0;
#ifdef HAVE_LTTNG_UST perf.lttng.end(perf.name);
perf.lttng.end();
#endif
} }
void Perf::count(Util::perf_counter_t pc) void Perf::count(Util::perf_counter_t pc)
@ -161,10 +157,7 @@ void Perf::count(Util::perf_counter_t pc)
_update_count++; _update_count++;
perf.count++; perf.count++;
#ifdef HAVE_LTTNG_UST perf.lttng.count(perf.name, perf.count);
perf.lttng.count();
#endif
} }
Util::perf_counter_t Perf::add(Util::perf_counter_type type, const char *name) Util::perf_counter_t Perf::add(Util::perf_counter_type type, const char *name)

View File

@ -37,17 +37,12 @@ public:
Perf_Counter(perf_counter_type type_, const char *name_) Perf_Counter(perf_counter_type type_, const char *name_)
: name{name_} : name{name_}
, type{type_} , type{type_}
#ifdef HAVE_LTTNG_UST
, lttng{name_}
#endif
, least{ULONG_MAX} , least{ULONG_MAX}
{ {
} }
const char *name; const char *name;
#ifdef HAVE_LTTNG_UST
Perf_Lttng lttng; Perf_Lttng lttng;
#endif
perf_counter_type type; perf_counter_type type;

View File

@ -19,32 +19,35 @@
#include <string.h> #include <string.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_Linux.h" #include "AP_HAL_Linux.h"
#include "Perf_Lttng_TracePoints.h" #include "Perf_Lttng_TracePoints.h"
#include "Perf_Lttng.h" #include "Perf_Lttng.h"
using namespace Linux; using namespace Linux;
Perf_Lttng::Perf_Lttng(const char *name) void Perf_Lttng::begin(const char *name)
{ {
strncpy(_name, name, MAX_TRACEPOINT_NAME_LEN); tracepoint(ardupilot, begin, name);
} }
void Perf_Lttng::begin() void Perf_Lttng::end(const char *name)
{ {
tracepoint(ardupilot, begin, _name); tracepoint(ardupilot, end, name);
} }
void Perf_Lttng::end() void Perf_Lttng::count(const char *name, uint64_t val)
{ {
tracepoint(ardupilot, end, _name); tracepoint(ardupilot, count, name, val);
} }
void Perf_Lttng::count() #else
{
tracepoint(ardupilot, count, _name, ++_count); #include "Perf_Lttng.h"
}
using namespace Linux;
void Perf_Lttng::begin(const char *name) { }
void Perf_Lttng::end(const char *name) { }
void Perf_Lttng::count(const char *name, uint64_t val) { }
#endif #endif

View File

@ -14,23 +14,17 @@
*/ */
#pragma once #pragma once
#include <AP_HAL/Util.h> #include <inttypes.h>
#include "AP_HAL_Linux.h" #include "AP_HAL_Linux.h"
#define MAX_TRACEPOINT_NAME_LEN 128
namespace Linux { namespace Linux {
class Perf_Lttng { class Perf_Lttng {
public: public:
Perf_Lttng(const char *name); void begin(const char *name);
void begin(); void end(const char *name);
void end(); void count(const char *name, uint64_t val);
void count();
private:
char _name[MAX_TRACEPOINT_NAME_LEN];
uint64_t _count;
}; };
} }

View File

@ -28,7 +28,7 @@ TRACEPOINT_EVENT(
ardupilot, ardupilot,
begin, begin,
TP_ARGS( TP_ARGS(
char*, name_arg const char*, name_arg
), ),
TP_FIELDS( TP_FIELDS(
ctf_string(name_field, name_arg) ctf_string(name_field, name_arg)
@ -39,7 +39,7 @@ TRACEPOINT_EVENT(
ardupilot, ardupilot,
end, end,
TP_ARGS( TP_ARGS(
char*, name_arg const char*, name_arg
), ),
TP_FIELDS( TP_FIELDS(
ctf_string(name_field, name_arg) ctf_string(name_field, name_arg)
@ -50,7 +50,7 @@ TRACEPOINT_EVENT(
ardupilot, ardupilot,
count, count,
TP_ARGS( TP_ARGS(
char*, name_arg, const char*, name_arg,
int, count_arg int, count_arg
), ),
TP_FIELDS( TP_FIELDS(