-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
benchmark_autodiff.cc
150 lines (128 loc) · 4.18 KB
/
benchmark_autodiff.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
// @file
// Benchmarks for Acrobot autodiff, with and without MultibodyPlant.
//
// This program is a successor to Hongkai Dai's original benchmark; see #8482.
#include <benchmark/benchmark.h>
#include "drake/common/eigen_types.h"
#include "drake/common/find_resource.h"
#include "drake/common/pointer_cast.h"
#include "drake/examples/acrobot/acrobot_plant.h"
#include "drake/math/autodiff.h"
#include "drake/math/autodiff_gradient.h"
#include "drake/multibody/benchmarks/acrobot/make_acrobot_plant.h"
#include "drake/multibody/parsing/parser.h"
#include "drake/tools/performance/fixture_common.h"
using Eigen::MatrixXd;
using drake::multibody::MultibodyPlant;
using drake::systems::Context;
using drake::systems::System;
namespace drake {
namespace examples {
namespace acrobot {
namespace {
template <typename T>
class FixtureBase : public benchmark::Fixture {
public:
FixtureBase() {
tools::performance::AddMinMaxStatistics(this);
}
void Populate(const System<T>& plant) {
context_ = plant.CreateDefaultContext();
x_ = context_->get_continuous_state_vector().CopyToVector();
}
void InvalidateState() {
context_->NoteContinuousStateChange();
}
protected:
std::unique_ptr<Context<T>> context_;
VectorX<T> x_{};
};
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_);
}
protected:
std::unique_ptr<AcrobotPlant<T>> plant_{};
};
using AcrobotFixtureD = AcrobotFixture<double>;
using AcrobotFixtureAdx = AcrobotFixture<AutoDiffXd>;
// NOLINTNEXTLINE(runtime/references) cpplint disapproves of gbench choices.
BENCHMARK_F(AcrobotFixtureD, AcrobotDMassMatrix)(benchmark::State& state) {
for (auto _ : state) {
InvalidateState();
plant_->MassMatrix(*context_);
}
}
// NOLINTNEXTLINE(runtime/references) cpplint disapproves of gbench choices.
BENCHMARK_F(AcrobotFixtureAdx, AcrobotAdxMassMatrix)(benchmark::State& state) {
for (auto _ : state) {
InvalidateState();
plant_->MassMatrix(*context_);
}
}
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);
if constexpr (std::is_same_v<T, double>) {
plant_ = std::move(double_plant);
} else {
plant_ = dynamic_pointer_cast<MultibodyPlant<AutoDiffXd>>(
double_plant->ToAutoDiffXd());
}
nv_ = plant_->num_velocities();
this->Populate(*plant_);
}
protected:
std::unique_ptr<MultibodyPlant<T>> plant_{};
int nv_{};
};
using MultibodyFixtureD = MultibodyFixture<double>;
using MultibodyFixtureAdx = MultibodyFixture<AutoDiffXd>;
// NOLINTNEXTLINE(runtime/references) cpplint disapproves of gbench choices.
BENCHMARK_F(MultibodyFixtureD, MultibodyDMassMatrix)(benchmark::State& state) {
MatrixXd M(nv_, nv_);
for (auto _ : state) {
InvalidateState();
plant_->CalcMassMatrix(*context_, &M);
}
}
BENCHMARK_F(MultibodyFixtureAdx, MultibodyAdxMassMatrix)
// NOLINTNEXTLINE(runtime/references) cpplint disapproves of gbench choices.
(benchmark::State& state) {
MatrixX<AutoDiffXd> M(nv_, nv_);
for (auto _ : state) {
InvalidateState();
plant_->CalcMassMatrix(*context_, &M);
}
}
BENCHMARK_F(MultibodyFixtureD, MultibodyDMassMatrixViaInverseDynamics)
// NOLINTNEXTLINE(runtime/references) cpplint disapproves of gbench choices.
(benchmark::State& state) {
MatrixXd M(nv_, nv_);
for (auto _ : state) {
InvalidateState();
plant_->CalcMassMatrixViaInverseDynamics(*context_, &M);
}
}
BENCHMARK_F(MultibodyFixtureAdx, MultibodyAdxMassMatrixViaInverseDynamics)
// NOLINTNEXTLINE(runtime/references) cpplint disapproves of gbench choices.
(benchmark::State& state) {
MatrixX<AutoDiffXd> M(nv_, nv_);
for (auto _ : state) {
InvalidateState();
plant_->CalcMassMatrixViaInverseDynamics(*context_, &M);
}
}
} // namespace
} // namespace acrobot
} // namespace examples
} // namespace drake
BENCHMARK_MAIN();