AP_Math: add benchmark for matrix multiplication

This commit is contained in:
Gustavo Jose de Sousa 2015-11-12 19:41:35 -02:00 committed by Andrew Tridgell
parent 2828f66a6a
commit eef784fbe6
2 changed files with 32 additions and 0 deletions

View File

@ -0,0 +1,22 @@
#include <AP_gbenchmark.h>
#include <AP_Math/AP_Math.h>
static void BM_MatrixMultiplication(benchmark::State& state)
{
Matrix3f m1(Vector3f(1.0f, 2.0f, 3.0f),
Vector3f(4.0f, 5.0f, 6.0f),
Vector3f(7.0f, 8.0f, 9.0f));
Matrix3f m2(Vector3f(1.0f, 2.0f, 3.0f),
Vector3f(4.0f, 5.0f, 6.0f),
Vector3f(7.0f, 8.0f, 9.0f));
while (state.KeepRunning()) {
Matrix3f m3 = m1 * m2;
gbenchmark_escape(&m3);
}
}
BENCHMARK(BM_MatrixMultiplication);
BENCHMARK_MAIN()

View File

@ -0,0 +1,10 @@
#!/usr/bin/env python
# encoding: utf-8
import ardupilotwaf
def build(bld):
ardupilotwaf.find_benchmarks(
bld,
use='ap',
)