Browse Source

AP_Math: add benchmark for matrix multiplication

master
Gustavo Jose de Sousa 9 years ago committed by Andrew Tridgell
parent
commit
eef784fbe6
  1. 22
      libraries/AP_Math/benchmarks/benchmark_matrix.cpp
  2. 10
      libraries/AP_Math/benchmarks/wscript

22
libraries/AP_Math/benchmarks/benchmark_matrix.cpp

@ -0,0 +1,22 @@ @@ -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()

10
libraries/AP_Math/benchmarks/wscript

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