From 6c1e9c60ed7ba930ee8bfc83cbb416698f6fee86 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 13 Apr 2020 14:02:40 -0400 Subject: [PATCH] tests: microbenchmarks reduce iterations and sleep inbetween --- src/systemcmds/tests/test_microbench_hrt.cpp | 5 +- src/systemcmds/tests/test_microbench_math.cpp | 107 +++++++++--------- .../tests/test_microbench_matrix.cpp | 17 +-- src/systemcmds/tests/test_microbench_uorb.cpp | 37 +++--- 4 files changed, 85 insertions(+), 81 deletions(-) diff --git a/src/systemcmds/tests/test_microbench_hrt.cpp b/src/systemcmds/tests/test_microbench_hrt.cpp index 739704302f..4c9178946c 100644 --- a/src/systemcmds/tests/test_microbench_hrt.cpp +++ b/src/systemcmds/tests/test_microbench_hrt.cpp @@ -74,6 +74,7 @@ void unlock() reset(); \ perf_counter_t p = perf_alloc(PC_ELAPSED, name); \ for (int i = 0; i < count; i++) { \ + px4_usleep(1); \ lock(); \ perf_begin(p); \ op; \ @@ -110,8 +111,8 @@ private: #endif } - uint64_t u_64; - uint64_t u_64_out; + volatile uint64_t u_64; + volatile uint64_t u_64_out; }; bool MicroBenchHRT::run_tests() diff --git a/src/systemcmds/tests/test_microbench_math.cpp b/src/systemcmds/tests/test_microbench_math.cpp index a8b91ce1ae..ecb3e4d477 100644 --- a/src/systemcmds/tests/test_microbench_math.cpp +++ b/src/systemcmds/tests/test_microbench_math.cpp @@ -75,6 +75,7 @@ void unlock() reset(); \ perf_counter_t p = perf_alloc(PC_ELAPSED, name); \ for (int i = 0; i < count; i++) { \ + px4_usleep(1); \ lock(); \ perf_begin(p); \ op; \ @@ -105,26 +106,26 @@ private: void reset(); - float f32; - float f32_out; + volatile float f32; + volatile float f32_out; - double f64; - double f64_out; + volatile double f64; + volatile double f64_out; - uint8_t i_8; - uint8_t i_8_out; + volatile uint8_t i_8; + volatile uint8_t i_8_out; - uint16_t i_16; - uint16_t i_16_out; + volatile uint16_t i_16; + volatile uint16_t i_16_out; - uint32_t i_32; - uint32_t i_32_out; + volatile uint32_t i_32; + volatile uint32_t i_32_out; - int64_t i_64; - int64_t i_64_out; + volatile int64_t i_64; + volatile int64_t i_64_out; - uint64_t u_64; - uint64_t u_64_out; + volatile uint64_t u_64; + volatile uint64_t u_64_out; }; bool MicroBenchMath::run_tests() @@ -179,50 +180,50 @@ ut_declare_test_c(test_microbench_math, MicroBenchMath) bool MicroBenchMath::time_single_precision_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); + PERF("float add", f32_out += f32, 100); + PERF("float sub", f32_out -= f32, 100); + PERF("float mul", f32_out *= f32, 100); + PERF("float div", f32_out /= f32, 100); + PERF("float sqrt", f32_out = sqrtf(f32), 100); return true; } bool MicroBenchMath::time_single_precision_float_trig() { - PERF("sinf()", f32_out = sinf(f32), 1000); - PERF("cosf()", f32_out = cosf(f32), 1000); - PERF("tanf()", f32_out = tanf(f32), 1000); + PERF("sinf()", f32_out = sinf(f32), 100); + PERF("cosf()", f32_out = cosf(f32), 100); + PERF("tanf()", f32_out = tanf(f32), 100); - PERF("acosf()", f32_out = acosf(f32), 1000); - PERF("asinf()", f32_out = asinf(f32), 1000); - PERF("atan2f()", f32_out = atan2f(f32, 2.0f * f32), 1000); + PERF("acosf()", f32_out = acosf(f32), 100); + PERF("asinf()", f32_out = asinf(f32), 100); + PERF("atan2f()", f32_out = atan2f(f32, 2.0f * f32), 100); return true; } bool MicroBenchMath::time_double_precision_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); + PERF("double add", f64_out += f64, 100); + PERF("double sub", f64_out -= f64, 100); + PERF("double mul", f64_out *= f64, 100); + PERF("double div", f64_out /= f64, 100); + PERF("double sqrt", f64_out = sqrt(f64), 100); return true; } bool MicroBenchMath::time_double_precision_float_trig() { - PERF("sin()", f64_out = sin(f64), 1000); - PERF("cos()", f64_out = cos(f64), 1000); - PERF("tan()", f64_out = tan(f64), 1000); + PERF("sin()", f64_out = sin(f64), 100); + PERF("cos()", f64_out = cos(f64), 100); + PERF("tan()", f64_out = tan(f64), 100); - 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("acos()", f64_out = acos(f64 * 0.5), 100); + PERF("asin()", f64_out = asin(f64 * 0.6), 100); + PERF("atan2()", f64_out = atan2(f64 * 0.7, f64 * 0.8), 100); - PERF("sqrt()", f64_out = sqrt(f64), 1000); + PERF("sqrt()", f64_out = sqrt(f64), 100); return true; } @@ -230,40 +231,40 @@ bool MicroBenchMath::time_double_precision_float_trig() bool MicroBenchMath::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); + PERF("int8 add", i_8_out += i_8, 100); + PERF("int8 sub", i_8_out -= i_8, 100); + PERF("int8 mul", i_8_out *= i_8, 100); + PERF("int8 div", i_8_out /= i_8, 100); return true; } bool MicroBenchMath::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); + PERF("int16 add", i_16_out += i_16, 100); + PERF("int16 sub", i_16_out -= i_16, 100); + PERF("int16 mul", i_16_out *= i_16, 100); + PERF("int16 div", i_16_out /= i_16, 100); return true; } bool MicroBenchMath::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); + PERF("int32 add", i_32_out += i_32, 100); + PERF("int32 sub", i_32_out -= i_32, 100); + PERF("int32 mul", i_32_out *= i_32, 100); + PERF("int32 div", i_32_out /= i_32, 100); return true; } bool MicroBenchMath::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); + PERF("int64 add", i_64_out += i_64, 100); + PERF("int64 sub", i_64_out -= i_64, 100); + PERF("int64 mul", i_64_out *= i_64, 100); + PERF("int64 div", i_64_out /= i_64, 100); return true; } diff --git a/src/systemcmds/tests/test_microbench_matrix.cpp b/src/systemcmds/tests/test_microbench_matrix.cpp index 86c00fc8b8..edf1459325 100644 --- a/src/systemcmds/tests/test_microbench_matrix.cpp +++ b/src/systemcmds/tests/test_microbench_matrix.cpp @@ -76,6 +76,7 @@ void unlock() reset(); \ perf_counter_t p = perf_alloc(PC_ELAPSED, name); \ for (int i = 0; i < count; i++) { \ + px4_usleep(1); \ lock(); \ perf_begin(p); \ op; \ @@ -145,17 +146,17 @@ ut_declare_test_c(test_microbench_matrix, MicroBenchMatrix) bool MicroBenchMatrix::time_px4_matrix() { - PERF("matrix Euler from Quaternion", e = q, 1000); - PERF("matrix Euler from Dcm", e = d, 1000); + PERF("matrix Euler from Quaternion", e = q, 100); + PERF("matrix Euler from Dcm", e = d, 100); - PERF("matrix Quaternion from Euler", q = e, 1000); - PERF("matrix Quaternion from Dcm", q = d, 1000); + PERF("matrix Quaternion from Euler", q = e, 100); + PERF("matrix Quaternion from Dcm", q = d, 100); - PERF("matrix Dcm from Euler", d = e, 1000); - PERF("matrix Dcm from Quaternion", d = q, 1000); + PERF("matrix Dcm from Euler", d = e, 100); + PERF("matrix Dcm from Quaternion", d = q, 100); - PERF("matrix 6x16 pseudo inverse (all non-zero columns)", A16 = matrix::geninv(B16), 1000); - PERF("matrix 6x16 pseudo inverse (4 non-zero columns)", A16 = matrix::geninv(B16_4), 1000); + PERF("matrix 6x16 pseudo inverse (all non-zero columns)", A16 = matrix::geninv(B16), 100); + PERF("matrix 6x16 pseudo inverse (4 non-zero columns)", A16 = matrix::geninv(B16_4), 100); return true; } diff --git a/src/systemcmds/tests/test_microbench_uorb.cpp b/src/systemcmds/tests/test_microbench_uorb.cpp index 43ace7fdcf..14feeaf3da 100644 --- a/src/systemcmds/tests/test_microbench_uorb.cpp +++ b/src/systemcmds/tests/test_microbench_uorb.cpp @@ -80,6 +80,7 @@ void unlock() reset(); \ perf_counter_t p = perf_alloc(PC_ELAPSED, name); \ for (int i = 0; i < count; i++) { \ + px4_usleep(1); \ lock(); \ perf_begin(p); \ op; \ @@ -149,18 +150,18 @@ bool MicroBenchORB::time_px4_uorb() bool updated = false; uint64_t time = 0; - PERF("orb_check vehicle_status", ret = orb_check(fd_status, &updated), 1000); - PERF("orb_copy vehicle_status", ret = orb_copy(ORB_ID(vehicle_status), fd_status, &status), 1000); + PERF("orb_check vehicle_status", ret = orb_check(fd_status, &updated), 100); + PERF("orb_copy vehicle_status", ret = orb_copy(ORB_ID(vehicle_status), fd_status, &status), 100); printf("\n"); - PERF("orb_check vehicle_local_position", ret = orb_check(fd_lpos, &updated), 1000); - PERF("orb_copy vehicle_local_position", ret = orb_copy(ORB_ID(vehicle_local_position), fd_lpos, &lpos), 1000); + PERF("orb_check vehicle_local_position", ret = orb_check(fd_lpos, &updated), 100); + PERF("orb_copy vehicle_local_position", ret = orb_copy(ORB_ID(vehicle_local_position), fd_lpos, &lpos), 100); printf("\n"); - PERF("orb_check sensor_gyro", ret = orb_check(fd_gyro, &updated), 1000); - PERF("orb_copy sensor_gyro", ret = orb_copy(ORB_ID(sensor_gyro), fd_gyro, &gyro), 1000); + PERF("orb_check sensor_gyro", ret = orb_check(fd_gyro, &updated), 100); + PERF("orb_copy sensor_gyro", ret = orb_copy(ORB_ID(sensor_gyro), fd_gyro, &gyro), 100); printf("\n"); @@ -190,41 +191,41 @@ bool MicroBenchORB::time_px4_uorb_direct() uint64_t time = 0; uORB::Subscription vstatus{ORB_ID(vehicle_status)}; - PERF("uORB::Subscription orb_check vehicle_status", ret = vstatus.updated(), 1000); - PERF("uORB::Subscription orb_copy vehicle_status", ret = vstatus.copy(&status), 1000); + PERF("uORB::Subscription orb_check vehicle_status", ret = vstatus.updated(), 100); + PERF("uORB::Subscription orb_copy vehicle_status", ret = vstatus.copy(&status), 100); printf("\n"); uORB::Subscription local_pos{ORB_ID(vehicle_local_position)}; - PERF("uORB::Subscription orb_check vehicle_local_position", ret = local_pos.updated(), 1000); - PERF("uORB::Subscription orb_copy vehicle_local_position", ret = local_pos.copy(&lpos), 1000); + PERF("uORB::Subscription orb_check vehicle_local_position", ret = local_pos.updated(), 100); + PERF("uORB::Subscription orb_copy vehicle_local_position", ret = local_pos.copy(&lpos), 100); { printf("\n"); uORB::Subscription sens_gyro0{ORB_ID(sensor_gyro), 0}; - PERF("uORB::Subscription orb_check sensor_gyro:0", ret = sens_gyro0.updated(), 1000); - PERF("uORB::Subscription orb_copy sensor_gyro:0", ret = sens_gyro0.copy(&gyro), 1000); + PERF("uORB::Subscription orb_check sensor_gyro:0", ret = sens_gyro0.updated(), 100); + PERF("uORB::Subscription orb_copy sensor_gyro:0", ret = sens_gyro0.copy(&gyro), 100); } { printf("\n"); uORB::Subscription sens_gyro1{ORB_ID(sensor_gyro), 1}; - PERF("uORB::Subscription orb_check sensor_gyro:1", ret = sens_gyro1.updated(), 1000); - PERF("uORB::Subscription orb_copy sensor_gyro:1", ret = sens_gyro1.copy(&gyro), 1000); + PERF("uORB::Subscription orb_check sensor_gyro:1", ret = sens_gyro1.updated(), 100); + PERF("uORB::Subscription orb_copy sensor_gyro:1", ret = sens_gyro1.copy(&gyro), 100); } { printf("\n"); uORB::Subscription sens_gyro2{ORB_ID(sensor_gyro), 2}; - PERF("uORB::Subscription orb_check sensor_gyro:2", ret = sens_gyro2.updated(), 1000); - PERF("uORB::Subscription orb_copy sensor_gyro:2", ret = sens_gyro2.copy(&gyro), 1000); + PERF("uORB::Subscription orb_check sensor_gyro:2", ret = sens_gyro2.updated(), 100); + PERF("uORB::Subscription orb_copy sensor_gyro:2", ret = sens_gyro2.copy(&gyro), 100); } { printf("\n"); uORB::Subscription sens_gyro3{ORB_ID(sensor_gyro), 3}; - PERF("uORB::Subscription orb_check sensor_gyro:3", ret = sens_gyro3.updated(), 1000); - PERF("uORB::Subscription orb_copy sensor_gyro:3", ret = sens_gyro3.copy(&gyro), 1000); + PERF("uORB::Subscription orb_check sensor_gyro:3", ret = sens_gyro3.updated(), 100); + PERF("uORB::Subscription orb_copy sensor_gyro:3", ret = sens_gyro3.copy(&gyro), 100); } return true;