diff --git a/README.md b/README.md index 96a0d6b30c0b9aa61ac7f661cfe0c306fd5b44e1..df6b6e6885f9a56aa70f926ff7c8a6899da03485 100644 --- a/README.md +++ b/README.md @@ -103,4 +103,8 @@ popd ./prefix/bin/rbdl-bench models/romeo/romeo_description/urdf/romeo.urdf ./prefix/bin/pinocchio-bench models/simple_humanoid.urdf ./prefix/bin/pinocchio-bench models/romeo/romeo_description/urdf/romeo.urdf +sudo cpupower frequency-set --governor performance +./prefix/bin/pinocchio-benchmark +./prefix/bin/rbdl-benchmark +sudo cpupower frequency-set --governor powersave ``` diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index fc15aca6e2b787a13a95d7290580cb2f78a2de5d..fc84ba5af6c983af4a41f697dcafe9a59e27cae1 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -9,8 +9,16 @@ ADD_EXECUTABLE(pinocchio-bench pinocchio-bench) PKG_CONFIG_USE_DEPENDENCY(pinocchio-bench pinocchio) INSTALL(TARGETS pinocchio-bench RUNTIME DESTINATION bin) +# RBDL & benchmark +ADD_EXECUTABLE(rbdl-benchmark rbdl-benchmark) +PKG_CONFIG_USE_DEPENDENCY(rbdl-benchmark rbdl) +PKG_CONFIG_USE_DEPENDENCY(rbdl-benchmark benchmark) +TARGET_LINK_LIBRARIES(rbdl-benchmark rbdl_urdfreader pthread) +INSTALL(TARGETS rbdl-benchmark RUNTIME DESTINATION bin) + # Pinocchio & benchmark ADD_EXECUTABLE(pinocchio-benchmark pinocchio-benchmark) -PKG_CONFIG_USE_DEPENDENCY(pinocchio-bench pinocchio) -PKG_CONFIG_USE_DEPENDENCY(pinocchio-bench benchmark) +PKG_CONFIG_USE_DEPENDENCY(pinocchio-benchmark pinocchio) +PKG_CONFIG_USE_DEPENDENCY(pinocchio-benchmark benchmark) +TARGET_LINK_LIBRARIES(pinocchio-benchmark pthread) INSTALL(TARGETS pinocchio-benchmark RUNTIME DESTINATION bin) diff --git a/src/rbdl-benchmark.cpp b/src/rbdl-benchmark.cpp new file mode 100644 index 0000000000000000000000000000000000000000..2984fe9f64aa8d7d4ed68096ac51aef816bf9d59 --- /dev/null +++ b/src/rbdl-benchmark.cpp @@ -0,0 +1,43 @@ +#include <iostream> +#include <fstream> + +#include <benchmark/benchmark.h> + +#include <rbdl/rbdl.h> +#include <rbdl/addons/urdfreader/urdfreader.h> + +static void BM_RBDL_RNEA(benchmark::State& state) +{ + RigidBodyDynamics::Model* model = new RigidBodyDynamics::Model(); + + // Load an urdf file provided by the user + RigidBodyDynamics::Addons::URDFReadFromFile("models/simple_humanoid.urdf", model, true); + std::cout << "RBDL Benchmark" << std::endl; + std::cout << " model: " << "models/simple_humanoid.urdf" << std::endl; + std::cout << " nq: " << model->q_size << std::endl; + std::cout << " nv: " << model->qdot_size << std::endl; + + RigidBodyDynamics::Math::VectorNd q = + RigidBodyDynamics::Math::VectorNd::Random(model->q_size); + RigidBodyDynamics::Math::VectorNd qdot = + RigidBodyDynamics::Math::VectorNd::Random(model->qdot_size); + RigidBodyDynamics::Math::VectorNd tau = + RigidBodyDynamics::Math::VectorNd::Random(model->qdot_size); + RigidBodyDynamics::Math::VectorNd qddot = + RigidBodyDynamics::Math::VectorNd::Random(model->qdot_size); + + for (auto _: state) + { + q = RigidBodyDynamics::Math::VectorNd::Random(model->q_size); + qdot = RigidBodyDynamics::Math::VectorNd::Random(model->qdot_size); + tau = RigidBodyDynamics::Math::VectorNd::Random(model->qdot_size); + qddot = RigidBodyDynamics::Math::VectorNd::Random(model->qdot_size); + + RigidBodyDynamics::ForwardDynamics(*model, q, qdot, tau, qddot); + //std::cout << "qddot after ABA: " << qddot.transpose() << std::endl; + } +} + +BENCHMARK(BM_RBDL_RNEA); + +BENCHMARK_MAIN();