40 #include <benchmark/benchmark.h>
43 #include <kdl/treejnttojacsolver.hpp>
54 Eigen::Isometry3d createTestIsometry()
57 return Eigen::Translation3d(1, 2, 3) * Eigen::AngleAxisd(0.13 *
M_PI, Eigen::Vector3d::UnitX()) *
58 Eigen::AngleAxisd(0.29 *
M_PI, Eigen::Vector3d::UnitY()) *
59 Eigen::AngleAxisd(0.42 *
M_PI, Eigen::Vector3d::UnitZ());
66 Eigen::Isometry3d isometry = createTestIsometry();
67 Eigen::Affine3d result;
70 benchmark::DoNotOptimize(result.affine().noalias() = isometry.affine() * isometry.matrix());
71 benchmark::ClobberMemory();
78 Eigen::Isometry3d isometry = createTestIsometry();
79 Eigen::Isometry3d result;
82 benchmark::DoNotOptimize(result.matrix().noalias() = isometry.matrix() * isometry.matrix());
83 benchmark::ClobberMemory();
90 Eigen::Isometry3d isometry = createTestIsometry();
91 Eigen::Isometry3d result;
94 benchmark::DoNotOptimize(result.affine().noalias() = isometry.affine() * isometry.matrix());
95 benchmark::ClobberMemory();
102 Eigen::Isometry3d isometry = createTestIsometry();
103 Eigen::Isometry3d result;
106 benchmark::DoNotOptimize(result.matrix() = isometry.matrix() * isometry.matrix());
107 benchmark::ClobberMemory();
113 Eigen::Isometry3d isometry = createTestIsometry();
114 Eigen::Isometry3d result;
117 benchmark::DoNotOptimize(result = isometry * isometry);
118 benchmark::ClobberMemory();
125 Eigen::Isometry3d isometry = createTestIsometry();
126 Eigen::Isometry3d result;
129 benchmark::DoNotOptimize(result = isometry.inverse());
130 benchmark::ClobberMemory();
137 Eigen::Affine3d affine = createTestIsometry();
138 Eigen::Affine3d result;
141 benchmark::DoNotOptimize(result = affine.inverse(Eigen::Isometry));
142 benchmark::ClobberMemory();
149 Eigen::Affine3d affine = createTestIsometry();
150 Eigen::Affine3d result;
153 benchmark::DoNotOptimize(result = affine.inverse());
154 benchmark::ClobberMemory();
161 Eigen::Affine3d affine = createTestIsometry();
162 Eigen::Affine3d result;
165 benchmark::DoNotOptimize(result = affine.matrix().inverse());
166 benchmark::ClobberMemory();
172 void SetUp(const ::benchmark::State& )
override
182 std::vector<moveit::core::RobotState> states;
184 for (
size_t i = 0; i < num; i++)
190 std::vector<moveit::core::RobotState> states;
192 for (
size_t i = 0; i < num; i++)
193 states.emplace_back(state);
199 std::vector<size_t> result;
201 for (
size_t i = 0; i < num; i++)
204 std::random_device random_device;
205 std::mt19937 generator(random_device());
207 std::shuffle(result.begin(), result.end(), generator);
219 auto states = constructStates(st.range(0));
220 benchmark::DoNotOptimize(states);
221 benchmark::ClobberMemory();
234 auto states = constructStates(st.range(0), state);
235 benchmark::DoNotOptimize(states);
236 benchmark::ClobberMemory();
243 auto states = constructStates(st.range(0));
244 auto permutation = randomPermudation(states.size());
247 for (
auto i : permutation)
249 states[i].setToRandomPositions();
262 st.SkipWithError(
"The planning group doesn't exist.");
287 st.SkipWithError(
"The planning group doesn't exist.");
293 st.SkipWithError(
"Can't create KDL tree.");
297 KDL::TreeJntToJacSolver jacobian_solver(kdl_tree);
298 KDL::Jacobian jacobian(kdl_tree.getNrOfJoints());
299 KDL::JntArray kdl_q(kdl_tree.getNrOfJoints());
312 jacobian_solver.JntToJac(kdl_q, jacobian, tip_link);
328 ->RangeMultiplier(10)
330 ->Unit(benchmark::kMillisecond);
332 ->RangeMultiplier(10)
334 ->Unit(benchmark::kMillisecond);