Add benchmarks
This commit is contained in:
parent
9ff0d55736
commit
d4fc37c7a3
3
.gitmodules
vendored
3
.gitmodules
vendored
|
@ -1,3 +1,6 @@
|
|||
[submodule "libs/googletest"]
|
||||
path = libs/googletest
|
||||
url = https://github.com/google/googletest
|
||||
[submodule "libs/benchmark"]
|
||||
path = libs/benchmark
|
||||
url = https://github.com/google/benchmark
|
||||
|
|
25
build.gradle
25
build.gradle
|
@ -25,6 +25,31 @@ model {
|
|||
}
|
||||
}
|
||||
testSuites {
|
||||
falconlibraryBench(GoogleTestTestSuiteSpec) {
|
||||
testing $.components.falconlibrary
|
||||
|
||||
binaries.all {
|
||||
if (toolChain instanceof GccCompatibleToolChain) {
|
||||
linker.args << '-pthread'
|
||||
} else {
|
||||
// MSVC
|
||||
linker.args << 'shlwapi.lib'
|
||||
}
|
||||
if (!project.hasProperty("withBench"))
|
||||
tasks.withType(RunTestExecutable) { RunTestExecutable task ->
|
||||
task.enabled = false
|
||||
}
|
||||
}
|
||||
|
||||
sources.cpp {
|
||||
source {
|
||||
srcDir 'src/bench'
|
||||
include '**/*.cpp'
|
||||
}
|
||||
lib project: ':libs', library: 'googleBench', linkage: 'static'
|
||||
}
|
||||
}
|
||||
|
||||
falconlibraryTest(GoogleTestTestSuiteSpec) {
|
||||
testing $.components.falconlibrary
|
||||
|
||||
|
|
1
libs/benchmark
Submodule
1
libs/benchmark
Submodule
|
@ -0,0 +1 @@
|
|||
Subproject commit 04a9343fc9b7886591c65933b94d0cee7a915452
|
|
@ -2,6 +2,7 @@ apply plugin: "cpp"
|
|||
|
||||
ext.libroot = new File(rootProject.rootDir, "libs")
|
||||
ext.gtest_root = new File(libroot, "googletest/googletest")
|
||||
ext.gbench_root = new File(libroot, "benchmark")
|
||||
|
||||
model {
|
||||
components {
|
||||
|
@ -17,5 +18,30 @@ model {
|
|||
}
|
||||
}
|
||||
}
|
||||
googleBench(NativeLibrarySpec) {
|
||||
binaries.all {
|
||||
if (toolChain instanceof GccCompatibleToolChain) {
|
||||
cppCompiler.args << '-std=c++14' << '-Wno-deprecated-declarations'
|
||||
linker.args << '-pthread'
|
||||
} else {
|
||||
// MSVC
|
||||
cppCompiler.args << '/std:c++14'
|
||||
linker.args << 'shlwapi.lib'
|
||||
}
|
||||
}
|
||||
|
||||
sources.cpp {
|
||||
source {
|
||||
srcDir new File(gbench_root, "src")
|
||||
include "**/*.cc"
|
||||
exclude "**/benchmark_main.cc"
|
||||
}
|
||||
exportedHeaders {
|
||||
srcDirs new File(gbench_root, "src"), new File(gbench_root, "include")
|
||||
include "**/*.hpp", "**/*.h"
|
||||
}
|
||||
lib project: ':libs', library: "googleTest", linkage: "static"
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
14
src/bench/bench_arc_param.cpp
Normal file
14
src/bench/bench_arc_param.cpp
Normal file
|
@ -0,0 +1,14 @@
|
|||
#include <FalconLibrary.h>
|
||||
#include <benchmark/benchmark.h>
|
||||
|
||||
static void BM_ArcParam(benchmark::State& state) {
|
||||
const frc5190::Pose2d initial{0.0, 0.0, frc5190::Rotation2d::FromDegrees(0.0)};
|
||||
const frc5190::Pose2d final{10.0, 10.0, frc5190::Rotation2d::FromDegrees(50.0)};
|
||||
const auto spline = std::make_shared<frc5190::ParametricQuinticHermiteSpline>(initial, final);
|
||||
|
||||
for (auto _ : state) {
|
||||
frc5190::SplineGenerator::ParameterizeSpline(spline, 2.0, 0.05, 0.1);
|
||||
}
|
||||
}
|
||||
|
||||
BENCHMARK(BM_ArcParam)->Arg(100)->Complexity()->Unit(benchmark::kMillisecond);
|
15
src/bench/bench_trajectory_generation.cpp
Normal file
15
src/bench/bench_trajectory_generation.cpp
Normal file
|
@ -0,0 +1,15 @@
|
|||
#include <FalconLibrary.h>
|
||||
#include <benchmark/benchmark.h>
|
||||
|
||||
static void BM_TrajectoryGeneration(benchmark::State& state) {
|
||||
const frc5190::Pose2d initial{0.0, 0.0, frc5190::Rotation2d::FromDegrees(0.0)};
|
||||
const frc5190::Pose2d final{10.0, 10.0, frc5190::Rotation2d::FromDegrees(50.0)};
|
||||
|
||||
for (auto _ : state) {
|
||||
frc5190::TrajectoryGenerator::GenerateTrajectory(
|
||||
std::vector<frc5190::Pose2d>{initial, final},
|
||||
std::vector<frc5190::TimingConstraint<frc5190::Pose2dWithCurvature>*>{}, 0.0, 0.0, 3., 2., false);
|
||||
}
|
||||
}
|
||||
|
||||
BENCHMARK(BM_TrajectoryGeneration)->Arg(100)->Complexity()->Unit(benchmark::kMillisecond);
|
4
src/bench/main.cpp
Normal file
4
src/bench/main.cpp
Normal file
|
@ -0,0 +1,4 @@
|
|||
#include <benchmark/benchmark.h>
|
||||
|
||||
BENCHMARK_MAIN();
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
#pragma once
|
||||
#include "../geometry/Pose2dWithCurvature.h"
|
||||
#include "../trajectory/TimedTrajectory.h"
|
||||
|
||||
#include "mathematics/trajectory/TimedTrajectory.h"
|
||||
|
||||
#include <memory>
|
||||
|
||||
|
|
|
@ -1,6 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
#include <vector>
|
||||
#include <memory>
|
||||
|
||||
#include "../geometry/Pose2dWithCurvature.h"
|
||||
#include "ParametricSpline.h"
|
||||
|
||||
|
|
|
@ -28,7 +28,7 @@ class TrajectoryGenerator {
|
|||
}
|
||||
}
|
||||
|
||||
const auto indexed_trajectory = TrajectoryFromSplineWaypoints(waypoints, 0.051, 0.00127, 0.1);
|
||||
const auto indexed_trajectory = TrajectoryFromSplineWaypoints(waypoints, 2.0, 0.05, 0.1);
|
||||
|
||||
auto points = indexed_trajectory.Points();
|
||||
|
||||
|
|
Loading…
Reference in New Issue
Block a user