tests simple timing microbenchmark

This commit is contained in:
Daniel Agar
2018-06-18 09:51:58 -04:00
committed by Lorenz Meier
parent 02d4405a62
commit 3ba97297d5
8 changed files with 253 additions and 8 deletions
+1
View File
@@ -21,6 +21,7 @@ set(tests
matrix
mavlink
mc_pos_control
microbench
mixer
param
parameters
+1
View File
@@ -105,6 +105,7 @@ protected:
_tests_passed++; \
} \
_cleanup(); \
printf("\n"); \
} while (0)
/// @brief Used to assert a value within a unit test.
+8 -8
View File
@@ -458,11 +458,11 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
float rms = sqrtf(pce->M2 / (pce->event_count - 1));
dprintf(fd, "%s: %llu events, %lluus elapsed, %lluus avg, min %lluus max %lluus %5.3fus rms\n",
dprintf(fd, "%s: %llu events, %lluus elapsed, %.2fus avg, min %lluus max %lluus %5.3fus rms\n",
handle->name,
(unsigned long long)pce->event_count,
(unsigned long long)pce->time_total,
(pce->event_count == 0) ? 0 : (unsigned long long)pce->time_total / pce->event_count,
(pce->event_count == 0) ? 0 : (double)pce->time_total / (double)pce->event_count,
(unsigned long long)pce->time_least,
(unsigned long long)pce->time_most,
(double)(1e6f * rms));
@@ -473,10 +473,10 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
float rms = sqrtf(pci->M2 / (pci->event_count - 1));
dprintf(fd, "%s: %llu events, %lluus avg, min %lluus max %lluus %5.3fus rms\n",
dprintf(fd, "%s: %llu events, %.2fus avg, min %lluus max %lluus %5.3fus rms\n",
handle->name,
(unsigned long long)pci->event_count,
(pci->event_count == 0) ? 0 : (unsigned long long)(pci->time_last - pci->time_first) / pci->event_count,
(pci->event_count == 0) ? 0 : (double)(pci->time_last - pci->time_first) / (double)pci->event_count,
(unsigned long long)pci->time_least,
(unsigned long long)pci->time_most,
(double)(1e6f * rms));
@@ -508,11 +508,11 @@ perf_print_counter_buffer(char *buffer, int length, perf_counter_t handle)
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
float rms = sqrtf(pce->M2 / (pce->event_count - 1));
num_written = snprintf(buffer, length, "%s: %llu events, %lluus elapsed, %lluus avg, min %lluus max %lluus %5.3fus rms",
num_written = snprintf(buffer, length, "%s: %llu events, %lluus elapsed, %.2fus avg, min %lluus max %lluus %5.3fus rms",
handle->name,
(unsigned long long)pce->event_count,
(unsigned long long)pce->time_total,
(pce->event_count == 0) ? 0 : (unsigned long long)pce->time_total / pce->event_count,
(pce->event_count == 0) ? 0 : (double)pce->time_total / (double)pce->event_count,
(unsigned long long)pce->time_least,
(unsigned long long)pce->time_most,
(double)(1e6f * rms));
@@ -523,10 +523,10 @@ perf_print_counter_buffer(char *buffer, int length, perf_counter_t handle)
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
float rms = sqrtf(pci->M2 / (pci->event_count - 1));
num_written = snprintf(buffer, length, "%s: %llu events, %lluus avg, min %lluus max %lluus %5.3fus rms",
num_written = snprintf(buffer, length, "%s: %llu events, %.2f avg, min %lluus max %lluus %5.3fus rms",
handle->name,
(unsigned long long)pci->event_count,
(pci->event_count == 0) ? 0 : (unsigned long long)(pci->time_last - pci->time_first) / pci->event_count,
(pci->event_count == 0) ? 0 : (double)(pci->time_last - pci->time_first) / (double)pci->event_count,
(unsigned long long)pci->time_least,
(unsigned long long)pci->time_most,
(double)(1e6f * rms));
+1
View File
@@ -52,4 +52,5 @@ px4_add_module(
drivers__device
git_ecl
ecl_validation
mathlib
)
+1
View File
@@ -49,6 +49,7 @@ set(srcs
test_led.c
test_mathlib.cpp
test_matrix.cpp
test_microbench.cpp
test_mixer.cpp
test_mount.c
test_param.c
+239
View File
@@ -0,0 +1,239 @@
#include <unit_test.h>
#include <time.h>
#include <stdlib.h>
#include <drivers/drv_hrt.h>
#include <perf/perf_counter.h>
#include <px4_config.h>
#include <px4_micro_hal.h>
#ifdef __PX4_NUTTX
#include <nuttx/irq.h>
static irqstate_t flags;
#endif
void lock()
{
#ifdef __PX4_NUTTX
flags = px4_enter_critical_section();
#endif
}
void unlock()
{
#ifdef __PX4_NUTTX
px4_leave_critical_section(flags);
#endif
}
#define PERF(name, op, count) do { \
usleep(1000); \
reset(); \
perf_counter_t p = perf_alloc(PC_ELAPSED, name); \
for (int i = 0; i < count; i++) { \
lock(); \
perf_begin(p); \
op; \
perf_end(p); \
unlock(); \
reset(); \
} \
perf_print_counter(p); \
perf_free(p); \
} while (0)
class MicroBench : public UnitTest
{
public:
virtual bool run_tests();
private:
bool time_single_prevision_float();
bool time_single_prevision_float_trig();
bool time_double_prevision_float();
bool time_double_prevision_float_trig();
bool time_8bit_integers();
bool time_16bit_integers();
bool time_32bit_integers();
bool time_64bit_integers();
bool time_px4_hrt();
void reset();
volatile float f32;
volatile float f32_out;
volatile double f64;
volatile double f64_out;
volatile uint8_t i_8;
volatile uint8_t i_8_out;
volatile uint16_t i_16;
volatile uint16_t i_16_out;
volatile uint32_t i_32;
volatile uint32_t i_32_out;
volatile int64_t i_64;
volatile int64_t i_64_out;
volatile uint64_t u_64;
volatile uint64_t u_64_out;
};
bool MicroBench::run_tests()
{
ut_run_test(time_single_prevision_float);
ut_run_test(time_single_prevision_float_trig);
ut_run_test(time_double_prevision_float);
ut_run_test(time_double_prevision_float_trig);
ut_run_test(time_8bit_integers);
ut_run_test(time_16bit_integers);
ut_run_test(time_32bit_integers);
ut_run_test(time_64bit_integers);
ut_run_test(time_px4_hrt);
return (_tests_failed == 0);
}
template<typename T>
T random(T min, T max)
{
const T scale = rand() / (T) RAND_MAX; /* [0, 1.0] */
return min + scale * (max - min); /* [min, max] */
}
void MicroBench::reset()
{
srand(time(nullptr));
// initialize with random data
f32 = random(-2.0f * M_PI, 2.0f * M_PI); // somewhat representative range for angles in radians
f32_out = random(-2.0f * M_PI, 2.0f * M_PI);
f64 = random(-2.0 * M_PI, 2.0 * M_PI);
f64_out = random(-2.0 * M_PI, 2.0 * M_PI);
i_8 = rand();
i_8_out = rand();
i_16 = rand();
i_16_out = rand();
i_32 = rand();
i_32_out = rand();
i_64 = rand();
i_64_out = rand();
u_64 = rand();
u_64_out = rand();
}
ut_declare_test_c(test_microbench, MicroBench)
bool MicroBench::time_single_prevision_float()
{
PERF("float add", f32_out += f32, 1000);
PERF("float sub", f32_out -= f32, 1000);
PERF("float mul", f32_out *= f32, 1000);
PERF("float div", f32_out /= f32, 1000);
PERF("float sqrt", f32_out = sqrtf(f32), 1000);
return true;
}
bool MicroBench::time_single_prevision_float_trig()
{
PERF("sinf()", f32_out = sinf(f32), 1000);
PERF("cosf()", f32_out = cosf(f32), 1000);
PERF("tanf()", f32_out = tanf(f32), 1000);
PERF("acosf()", f32_out = acosf(f32), 1000);
PERF("asinf()", f32_out = asinf(f32), 1000);
PERF("atan2f()", f32_out = atan2f(f32, 2.0f * f32), 1000);
return true;
}
bool MicroBench::time_double_prevision_float()
{
PERF("double add", f64_out += f64, 1000);
PERF("double sub", f64_out -= f64, 1000);
PERF("double mul", f64_out *= f64, 1000);
PERF("double div", f64_out /= f64, 1000);
PERF("double sqrt", f64_out = sqrt(f64), 1000);
return true;
}
bool MicroBench::time_double_prevision_float_trig()
{
PERF("sin()", f64_out = sin(f64), 1000);
PERF("cos()", f64_out = cos(f64), 1000);
PERF("tan()", f64_out = tan(f64), 1000);
PERF("acos()", f64_out = acos(f64 * 0.5), 1000);
PERF("asin()", f64_out = asin(f64 * 0.6), 1000);
PERF("atan2()", f64_out = atan2(f64 * 0.7, f64 * 0.8), 1000);
PERF("sqrt()", f64_out = sqrt(f64), 1000);
return true;
}
bool MicroBench::time_8bit_integers()
{
PERF("int8 add", i_8_out += i_8, 1000);
PERF("int8 sub", i_8_out -= i_8, 1000);
PERF("int8 mul", i_8_out *= i_8, 1000);
PERF("int8 div", i_8_out /= i_8, 1000);
return true;
}
bool MicroBench::time_16bit_integers()
{
PERF("int16 add", i_16_out += i_16, 1000);
PERF("int16 sub", i_16_out -= i_16, 1000);
PERF("int16 mul", i_16_out *= i_16, 1000);
PERF("int16 div", i_16_out /= i_16, 1000);
return true;
}
bool MicroBench::time_32bit_integers()
{
PERF("int32 add", i_32_out += i_32, 1000);
PERF("int32 sub", i_32_out -= i_32, 1000);
PERF("int32 mul", i_32_out *= i_32, 1000);
PERF("int32 div", i_32_out /= i_32, 1000);
return true;
}
bool MicroBench::time_64bit_integers()
{
PERF("int64 add", i_64_out += i_64, 1000);
PERF("int64 sub", i_64_out -= i_64, 1000);
PERF("int64 mul", i_64_out *= i_64, 1000);
PERF("int64 div", i_64_out /= i_64, 1000);
return true;
}
bool MicroBench::time_px4_hrt()
{
PERF("hrt_absolute_time()", u_64_out = hrt_absolute_time(), 1000);
PERF("hrt_elapsed_time()", u_64_out = hrt_elapsed_time(&u_64), 1000);
return true;
}
+1
View File
@@ -115,6 +115,7 @@ const struct {
{"jig_voltages", test_jig_voltages, OPT_NOALLTEST},
{"mathlib", test_mathlib, 0},
{"matrix", test_matrix, 0},
{"microbench", test_microbench, 0},
{"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
{"param", test_param, 0},
{"parameters", test_parameters, 0},
+1
View File
@@ -69,6 +69,7 @@ extern int test_jig_voltages(int argc, char *argv[]);
extern int test_led(int argc, char *argv[]);
extern int test_mathlib(int argc, char *argv[]);
extern int test_matrix(int argc, char *argv[]);
extern int test_microbench(int argc, char *argv[]);
extern int test_mixer(int argc, char *argv[]);
extern int test_mount(int argc, char *argv[]);
extern int test_param(int argc, char *argv[]);