diff --git a/src/Math/include/BipedalLocomotion/Math/LinearizedFrictionCone.h b/src/Math/include/BipedalLocomotion/Math/LinearizedFrictionCone.h index ce13425bc4..e25c8eff04 100644 --- a/src/Math/include/BipedalLocomotion/Math/LinearizedFrictionCone.h +++ b/src/Math/include/BipedalLocomotion/Math/LinearizedFrictionCone.h @@ -49,7 +49,7 @@ class LinearizedFrictionCone * | `static_friction_coefficient` | `double` | Static friction coefficient. | * @return true in case of success/false otherwise. */ - bool initialize(std::weak_ptr handler); + bool initialize(std::weak_ptr handler); /** * Get the matrix A. diff --git a/src/Math/src/LinearizedFrictionCone.cpp b/src/Math/src/LinearizedFrictionCone.cpp index 58bb4622c5..d043a5fe55 100644 --- a/src/Math/src/LinearizedFrictionCone.cpp +++ b/src/Math/src/LinearizedFrictionCone.cpp @@ -12,7 +12,7 @@ using namespace BipedalLocomotion::Math; -bool LinearizedFrictionCone::initialize(std::weak_ptr handler) +bool LinearizedFrictionCone::initialize(std::weak_ptr handler) { constexpr auto errorPrefix = "[LinearizedFrictionCone::initialize]";