Skip to content

Commit

Permalink
[workspace] Patch googlebenchmark to avoid shadow warnings (#19796)
Browse files Browse the repository at this point in the history
This allows us to remove copy-pasta in every benchmark we write.
  • Loading branch information
jwnimmer-tri authored Jul 16, 2023
1 parent 4aa538d commit 7cb3445
Show file tree
Hide file tree
Showing 8 changed files with 58 additions and 39 deletions.
3 changes: 1 addition & 2 deletions geometry/benchmarking/render_benchmark.cc
Original file line number Diff line number Diff line change
Expand Up @@ -84,8 +84,7 @@ class RenderBenchmark : public benchmark::Fixture {
material_.AddProperty("label", "id", RenderLabel::kDontCare);
}

using benchmark::Fixture::SetUp;
void SetUp(const ::benchmark::State&) { depth_cameras_.clear(); }
void SetUp(::benchmark::State&) { depth_cameras_.clear(); }

template <EngineType engine_type>
// NOLINTNEXTLINE(runtime/references)
Expand Down
2 changes: 0 additions & 2 deletions multibody/benchmarking/acrobot.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,6 @@ class FixtureBase : public benchmark::Fixture {
template <typename T>
class AcrobotFixture : public FixtureBase<T> {
public:
using benchmark::Fixture::SetUp;
void SetUp(benchmark::State&) override {
plant_ = std::make_unique<AcrobotPlant<T>>();
this->Populate(*plant_);
Expand Down Expand Up @@ -81,7 +80,6 @@ BENCHMARK_F(AcrobotFixtureAdx, AcrobotAdxMassMatrix)(benchmark::State& state) {
template <typename T>
class MultibodyFixture : public FixtureBase<T> {
public:
using benchmark::Fixture::SetUp;
void SetUp(benchmark::State&) override {
auto double_plant = multibody::benchmarks::acrobot::MakeAcrobotPlant(
multibody::benchmarks::acrobot::AcrobotParameters(), true);
Expand Down
60 changes: 33 additions & 27 deletions multibody/benchmarking/cassie.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,6 @@ using systems::ContinuousState;
using systems::FixedInputPortValue;
using systems::System;

// We use this alias to silence cpplint barking at mutable references.
using BenchmarkStateRef = benchmark::State&;

// In the benchmark case instantiations at the bottom of this file, we'll use
// a bitmask for the case's "Arg" to denote which quantities are in scope as
// either gradients (for T=AutoDiffXd) or variables (for T=Expression).
Expand All @@ -44,11 +41,7 @@ class Cassie : public benchmark::Fixture {
tools::performance::AddMinMaxStatistics(this);
}

// This apparently futile using statement works around "overloaded virtual"
// errors in g++. All of this is a consequence of the weird deprecation of
// const-ref State versions of SetUp() and TearDown() in benchmark.h.
using benchmark::Fixture::SetUp;
void SetUp(BenchmarkStateRef state) override {
void SetUp(benchmark::State& state) override {
SetUpNonZeroState();
SetUpGradientsOrVariables(state);
tools::performance::TareMemoryManager();
Expand Down Expand Up @@ -85,7 +78,8 @@ class Cassie : public benchmark::Fixture {
// For T=double, any request for gradients is an error.
// For T=AutoDiffXd, sets the specified gradients to the identity matrix.
// For T=Expression, sets the specified quantities to symbolic variables.
void SetUpGradientsOrVariables(BenchmarkStateRef state);
// NOLINTNEXTLINE(runtime/references)
void SetUpGradientsOrVariables(benchmark::State& state);

// Use these functions to invalidate input- or state-dependent computations
// each benchmarked step. Disabling the cache entirely would affect the
Expand All @@ -103,7 +97,8 @@ class Cassie : public benchmark::Fixture {
}

// Runs the MassMatrix benchmark.
void DoMassMatrix(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
void DoMassMatrix(benchmark::State& state) {
DRAKE_DEMAND(want_grad_vdot(state) == false);
DRAKE_DEMAND(want_grad_u(state) == false);
for (auto _ : state) {
Expand All @@ -113,7 +108,8 @@ class Cassie : public benchmark::Fixture {
}

// Runs the InverseDynamics benchmark.
void DoInverseDynamics(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
void DoInverseDynamics(benchmark::State& state) {
DRAKE_DEMAND(want_grad_u(state) == false);
for (auto _ : state) {
InvalidateState();
Expand All @@ -122,7 +118,8 @@ class Cassie : public benchmark::Fixture {
}

// Runs the ForwardDynamics benchmark.
void DoForwardDynamics(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
void DoForwardDynamics(benchmark::State& state) {
DRAKE_DEMAND(want_grad_vdot(state) == false);
for (auto _ : state) {
InvalidateInput();
Expand Down Expand Up @@ -195,16 +192,16 @@ void Cassie<T>::SetUpNonZeroState() {
mass_matrix_out_ = MatrixX<T>::Zero(nv_, nv_);
}

template <>
void Cassie<double>::SetUpGradientsOrVariables(BenchmarkStateRef state) {
template <> // NOLINTNEXTLINE(runtime/references)
void Cassie<double>::SetUpGradientsOrVariables(benchmark::State& state) {
DRAKE_DEMAND(want_grad_q(state) == false);
DRAKE_DEMAND(want_grad_v(state) == false);
DRAKE_DEMAND(want_grad_vdot(state) == false);
DRAKE_DEMAND(want_grad_u(state) == false);
}

template <>
void Cassie<AutoDiffXd>::SetUpGradientsOrVariables(BenchmarkStateRef state) {
template <> // NOLINTNEXTLINE(runtime/references)
void Cassie<AutoDiffXd>::SetUpGradientsOrVariables(benchmark::State& state) {
// For the quantities destined for InitializeAutoDiff, read their default
// values (without any gradients). For the others, leave the matrix empty.
VectorX<double> q, v, vdot, u;
Expand Down Expand Up @@ -241,8 +238,8 @@ void Cassie<AutoDiffXd>::SetUpGradientsOrVariables(BenchmarkStateRef state) {
}
}

template <>
void Cassie<Expression>::SetUpGradientsOrVariables(BenchmarkStateRef state) {
template <> // NOLINTNEXTLINE(runtime/references)
void Cassie<Expression>::SetUpGradientsOrVariables(benchmark::State& state) {
if (want_grad_q(state)) {
const VectorX<Expression> q = MakeVectorVariable(nq_, "q");
plant_->SetPositions(context_.get(), q);
Expand All @@ -269,28 +266,32 @@ void Cassie<Expression>::SetUpGradientsOrVariables(BenchmarkStateRef state) {
//
// For T=Expression, the range arg sets which variables to use, using a bitmask.

BENCHMARK_DEFINE_F(CassieDouble, MassMatrix)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieDouble, MassMatrix)(benchmark::State& state) {
DoMassMatrix(state);
}
BENCHMARK_REGISTER_F(CassieDouble, MassMatrix)
->Unit(benchmark::kMicrosecond)
->Arg(kWantNoGrad);

BENCHMARK_DEFINE_F(CassieDouble, InverseDynamics)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieDouble, InverseDynamics)(benchmark::State& state) {
DoInverseDynamics(state);
}
BENCHMARK_REGISTER_F(CassieDouble, InverseDynamics)
->Unit(benchmark::kMicrosecond)
->Arg(kWantNoGrad);

BENCHMARK_DEFINE_F(CassieDouble, ForwardDynamics)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieDouble, ForwardDynamics)(benchmark::State& state) {
DoForwardDynamics(state);
}
BENCHMARK_REGISTER_F(CassieDouble, ForwardDynamics)
->Unit(benchmark::kMicrosecond)
->Arg(kWantNoGrad);

BENCHMARK_DEFINE_F(CassieAutoDiff, MassMatrix)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieAutoDiff, MassMatrix)(benchmark::State& state) {
DoMassMatrix(state);
}
BENCHMARK_REGISTER_F(CassieAutoDiff, MassMatrix)
Expand All @@ -300,7 +301,8 @@ BENCHMARK_REGISTER_F(CassieAutoDiff, MassMatrix)
->Arg(kWantGradV)
->Arg(kWantGradX);

BENCHMARK_DEFINE_F(CassieAutoDiff, InverseDynamics)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieAutoDiff, InverseDynamics)(benchmark::State& state) {
DoInverseDynamics(state);
}
BENCHMARK_REGISTER_F(CassieAutoDiff, InverseDynamics)
Expand All @@ -314,7 +316,8 @@ BENCHMARK_REGISTER_F(CassieAutoDiff, InverseDynamics)
->Arg(kWantGradV|kWantGradVdot)
->Arg(kWantGradX|kWantGradVdot);

BENCHMARK_DEFINE_F(CassieAutoDiff, ForwardDynamics)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieAutoDiff, ForwardDynamics)(benchmark::State& state) {
DoForwardDynamics(state);
}
BENCHMARK_REGISTER_F(CassieAutoDiff, ForwardDynamics)
Expand All @@ -328,7 +331,8 @@ BENCHMARK_REGISTER_F(CassieAutoDiff, ForwardDynamics)
->Arg(kWantGradV|kWantGradU)
->Arg(kWantGradX|kWantGradU);

BENCHMARK_DEFINE_F(CassieExpression, MassMatrix)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieExpression, MassMatrix)(benchmark::State& state) {
DoMassMatrix(state);
}
BENCHMARK_REGISTER_F(CassieExpression, MassMatrix)
Expand All @@ -338,7 +342,8 @@ BENCHMARK_REGISTER_F(CassieExpression, MassMatrix)
->Arg(kWantGradV)
->Arg(kWantGradX);

BENCHMARK_DEFINE_F(CassieExpression, InverseDynamics)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieExpression, InverseDynamics)(benchmark::State& state) {
DoInverseDynamics(state);
}
BENCHMARK_REGISTER_F(CassieExpression, InverseDynamics)
Expand All @@ -352,7 +357,8 @@ BENCHMARK_REGISTER_F(CassieExpression, InverseDynamics)
->Arg(kWantGradV|kWantGradVdot)
->Arg(kWantGradX|kWantGradVdot);

BENCHMARK_DEFINE_F(CassieExpression, ForwardDynamics)(BenchmarkStateRef state) {
// NOLINTNEXTLINE(runtime/references)
BENCHMARK_DEFINE_F(CassieExpression, ForwardDynamics)(benchmark::State& state) {
DoForwardDynamics(state);
}
BENCHMARK_REGISTER_F(CassieExpression, ForwardDynamics)
Expand Down
3 changes: 1 addition & 2 deletions multibody/benchmarking/position_constraint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,7 @@ using systems::Context;

class IiwaPositionConstraintFixture : public benchmark::Fixture {
public:
using benchmark::Fixture::SetUp;
void SetUp(const ::benchmark::State&) override {
void SetUp(::benchmark::State&) override {
tools::performance::AddMinMaxStatistics(this);

const int kNumIiwas = 10;
Expand Down
4 changes: 0 additions & 4 deletions systems/benchmarking/framework_benchmarks.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,6 @@ class BasicFixture : public benchmark::Fixture {
public:
BasicFixture() { tools::performance::AddMinMaxStatistics(this); }

// This apparently futile using statement works around "overloaded virtual"
// errors in g++. All of this is a consequence of the weird deprecation of
// const-ref State versions of SetUp() and TearDown() in benchmark.h.
using benchmark::Fixture::SetUp;
void SetUp(benchmark::State&) override {
builder_ = std::make_unique<DiagramBuilder<double>>();
}
Expand Down
3 changes: 1 addition & 2 deletions systems/benchmarking/multilayer_perceptron_benchmark.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,7 @@ class Mlp : public benchmark::Fixture {
this->Unit(benchmark::kMicrosecond);
}

using benchmark::Fixture::SetUp;
void SetUp(const benchmark::State& state) {
void SetUp(benchmark::State& state) { // NOLINT(runtime/references)
// Number of inputs.
const int num_inputs = state.range(0);
DRAKE_DEMAND(num_inputs >= 1);
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
Avoid GCC warnings about overloaded virtuals

We only need the mutable spelling for Drake code.

--- include/benchmark/benchmark.h
+++ include/benchmark/benchmark.h
@@ -1425,12 +1425,8 @@
this->TearDown(st);
}

- // These will be deprecated ...
- virtual void SetUp(const State&) {}
- virtual void TearDown(const State&) {}
- // ... In favor of these.
- virtual void SetUp(State& st) { SetUp(const_cast<const State&>(st)); }
- virtual void TearDown(State& st) { TearDown(const_cast<const State&>(st)); }
+ virtual void SetUp(State&) {}
+ virtual void TearDown(State&) {}

protected:
virtual void BenchmarkCase(State&) = 0;
1 change: 1 addition & 0 deletions tools/workspace/googlebenchmark/repository.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ def googlebenchmark_repository(
mirrors = mirrors,
patches = [
":patches/console_allocs.patch",
":patches/remove_overloaded_fixture_set_up.patch",
":patches/string_precision.patch",
],
)

0 comments on commit 7cb3445

Please sign in to comment.