Skip to content

Commit

Permalink
Simplify/Fix Isometry inverse benchmarks
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Dec 21, 2023
1 parent 6d25448 commit 200acfb
Showing 1 changed file with 9 additions and 18 deletions.
27 changes: 9 additions & 18 deletions moveit_core/robot_state/test/robot_state_benchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,9 +125,9 @@ static void multiplyIsometryTimesIsometry(benchmark::State& st)
static void inverseIsometry3d(benchmark::State& st)
{
Eigen::Isometry3d isometry = createTestIsometry();
Eigen::Isometry3d result;
for (auto _ : st)
{
Eigen::Isometry3d result;
benchmark::DoNotOptimize(result = isometry.inverse());
benchmark::ClobberMemory();
}
Expand All @@ -136,43 +136,34 @@ static void inverseIsometry3d(benchmark::State& st)
// Benchmark time to invert an Eigen::Affine3d(Eigen::Isometry).
static void inverseAffineIsometry(benchmark::State& st)
{
Eigen::Isometry3d isometry = createTestIsometry();
Eigen::Affine3d affine;
affine.matrix() = isometry.matrix();

Eigen::Affine3d affine = createTestIsometry();
Eigen::Affine3d result;
for (auto _ : st)
{
Eigen::Affine3d result;
benchmark::DoNotOptimize(result = affine.inverse(Eigen::Isometry).affine());
benchmark::DoNotOptimize(result = affine.inverse(Eigen::Isometry));
benchmark::ClobberMemory();
}
}

// Benchmark time to invert an Eigen::Affine3d.
static void inverseAffine(benchmark::State& st)
{
Eigen::Isometry3d isometry = createTestIsometry();
Eigen::Affine3d affine;
affine.matrix() = isometry.matrix();

Eigen::Affine3d affine = createTestIsometry();
Eigen::Affine3d result;
for (auto _ : st)
{
Eigen::Affine3d result;
benchmark::DoNotOptimize(result = affine.inverse().affine());
benchmark::DoNotOptimize(result = affine.inverse());
benchmark::ClobberMemory();
}
}

// Benchmark time to invert an Eigen::Matrix4d.
static void inverseMatrix4d(benchmark::State& st)
{
Eigen::Isometry3d isometry = createTestIsometry();
Eigen::Affine3d affine;
affine.matrix() = isometry.matrix();

Eigen::Affine3d affine = createTestIsometry();
Eigen::Affine3d result;
for (auto _ : st)
{
Eigen::Affine3d result;
benchmark::DoNotOptimize(result = affine.matrix().inverse());
benchmark::ClobberMemory();
}
Expand Down

0 comments on commit 200acfb

Please sign in to comment.