From 84e69adadcd548174295b2d36e637cf8c392fd27 Mon Sep 17 00:00:00 2001 From: Giulio Romualdi Date: Fri, 26 Mar 2021 20:04:45 +0100 Subject: [PATCH] Fixed typos in ContinuousDynamicalSystem component --- .../ContinuousDynamicalSystem/DynamicalSystem.h | 6 +++--- .../ContinuousDynamicalSystem/FixedBaseDynamics.h | 2 +- .../FloatingBaseDynamicsWithCompliantContacts.h | 2 +- .../FloatingBaseSystemKinematics.h | 2 +- .../ContinuousDynamicalSystem/LinearTimeInvariantSystem.h | 2 +- src/ContinuousDynamicalSystem/src/FixedBaseDynamics.cpp | 4 ++-- .../src/FloatingBaseDynamicsWithCompliantContacts.cpp | 4 ++-- .../src/FloatingBaseSystemKinematics.cpp | 4 ++-- .../src/LinearTimeInvariantSystem.cpp | 2 +- 9 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/DynamicalSystem.h b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/DynamicalSystem.h index f9f014dd02..c29734d3f5 100644 --- a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/DynamicalSystem.h +++ b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/DynamicalSystem.h @@ -92,7 +92,7 @@ template class DynamicalSystem * @param handler pointer to the parameter handler. * @return true in case of success/false otherwise. */ - bool initalize(std::weak_ptr handler); + bool initialize(std::weak_ptr handler); /** * Set the state of the dynamical system. @@ -131,10 +131,10 @@ template class DynamicalSystem }; template -bool DynamicalSystem<_Derived>::initalize( +bool DynamicalSystem<_Derived>::initialize( std::weak_ptr handler) { - return this->derived().initalize(handler); + return this->derived().initialize(handler); } template bool DynamicalSystem<_Derived>::setState(const State& state) diff --git a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FixedBaseDynamics.h b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FixedBaseDynamics.h index 8113933eb3..476cd6781b 100644 --- a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FixedBaseDynamics.h +++ b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FixedBaseDynamics.h @@ -90,7 +90,7 @@ class FixedBaseDynamics : public DynamicalSystem * | `gravity` | `double` | Value of the Gravity. If not defined Math::StandardAccelerationOfGravitation is used | No | * @return true in case of success/false otherwise. */ - bool initalize(std::weak_ptr handler); + bool initialize(std::weak_ptr handler); /** * Set a kinDynComputations object. diff --git a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FloatingBaseDynamicsWithCompliantContacts.h b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FloatingBaseDynamicsWithCompliantContacts.h index cb537c88d9..1a0517e9b2 100644 --- a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FloatingBaseDynamicsWithCompliantContacts.h +++ b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FloatingBaseDynamicsWithCompliantContacts.h @@ -116,7 +116,7 @@ class FloatingBaseDynamicsWithCompliantContacts * | `rho` | `double` | Baumgarte stabilization parameter over the SO(3) group. The default value is 0.01 | No | * @return true in case of success/false otherwise. */ - bool initalize(std::weak_ptr handler); + bool initialize(std::weak_ptr handler); /** * Set a kinDynComputations object. diff --git a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FloatingBaseSystemKinematics.h b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FloatingBaseSystemKinematics.h index f6f50fe80c..3ea8689b68 100644 --- a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FloatingBaseSystemKinematics.h +++ b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/FloatingBaseSystemKinematics.h @@ -78,7 +78,7 @@ class FloatingBaseSystemKinematics : public DynamicalSystem handler); + bool initialize(std::weak_ptr handler); /** * Set the state of the dynamical system. diff --git a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/LinearTimeInvariantSystem.h b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/LinearTimeInvariantSystem.h index 55ec4e3249..fe81aa9477 100644 --- a/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/LinearTimeInvariantSystem.h +++ b/src/ContinuousDynamicalSystem/include/BipedalLocomotion/ContinuousDynamicalSystem/LinearTimeInvariantSystem.h @@ -75,7 +75,7 @@ class LinearTimeInvariantSystem : public DynamicalSystem handler); + bool initialize(std::weak_ptr handler); /** * Set the state of the dynamical system. diff --git a/src/ContinuousDynamicalSystem/src/FixedBaseDynamics.cpp b/src/ContinuousDynamicalSystem/src/FixedBaseDynamics.cpp index ab43bbb2b2..7f79a70aef 100644 --- a/src/ContinuousDynamicalSystem/src/FixedBaseDynamics.cpp +++ b/src/ContinuousDynamicalSystem/src/FixedBaseDynamics.cpp @@ -17,9 +17,9 @@ using namespace BipedalLocomotion; using namespace BipedalLocomotion::ContinuousDynamicalSystem; using namespace BipedalLocomotion::ParametersHandler; -bool FixedBaseDynamics::initalize(std::weak_ptr handler) +bool FixedBaseDynamics::initialize(std::weak_ptr handler) { - constexpr auto logPrefix = "[FixedBaseDynamics::initalize]"; + constexpr auto logPrefix = "[FixedBaseDynamics::initialize]"; auto ptr = handler.lock(); if (ptr == nullptr) diff --git a/src/ContinuousDynamicalSystem/src/FloatingBaseDynamicsWithCompliantContacts.cpp b/src/ContinuousDynamicalSystem/src/FloatingBaseDynamicsWithCompliantContacts.cpp index 25364b134b..e33bd6a02c 100644 --- a/src/ContinuousDynamicalSystem/src/FloatingBaseDynamicsWithCompliantContacts.cpp +++ b/src/ContinuousDynamicalSystem/src/FloatingBaseDynamicsWithCompliantContacts.cpp @@ -18,9 +18,9 @@ using namespace BipedalLocomotion; using namespace BipedalLocomotion::ContinuousDynamicalSystem; using namespace BipedalLocomotion::ParametersHandler; -bool FloatingBaseDynamicsWithCompliantContacts::initalize(std::weak_ptr handler) +bool FloatingBaseDynamicsWithCompliantContacts::initialize(std::weak_ptr handler) { - constexpr auto logPrefix = "[FloatingBaseDynamicsWithCompliantContacts::initalize]"; + constexpr auto logPrefix = "[FloatingBaseDynamicsWithCompliantContacts::initialize]"; auto ptr = handler.lock(); if (ptr == nullptr) diff --git a/src/ContinuousDynamicalSystem/src/FloatingBaseSystemKinematics.cpp b/src/ContinuousDynamicalSystem/src/FloatingBaseSystemKinematics.cpp index bd70cc07b7..429b01e38c 100644 --- a/src/ContinuousDynamicalSystem/src/FloatingBaseSystemKinematics.cpp +++ b/src/ContinuousDynamicalSystem/src/FloatingBaseSystemKinematics.cpp @@ -11,9 +11,9 @@ using namespace BipedalLocomotion::ContinuousDynamicalSystem; using namespace BipedalLocomotion::ParametersHandler; -bool FloatingBaseSystemKinematics::initalize(std::weak_ptr handler) +bool FloatingBaseSystemKinematics::initialize(std::weak_ptr handler) { - constexpr auto logPrefix = "[FloatingBaseSystemKinematics::initalize]"; + constexpr auto logPrefix = "[FloatingBaseSystemKinematics::initialize]"; auto ptr = handler.lock(); if (ptr == nullptr) diff --git a/src/ContinuousDynamicalSystem/src/LinearTimeInvariantSystem.cpp b/src/ContinuousDynamicalSystem/src/LinearTimeInvariantSystem.cpp index c3f1c7d719..87302ef15e 100644 --- a/src/ContinuousDynamicalSystem/src/LinearTimeInvariantSystem.cpp +++ b/src/ContinuousDynamicalSystem/src/LinearTimeInvariantSystem.cpp @@ -68,7 +68,7 @@ bool LinearTimeInvariantSystem::dynamics(const double& time, StateDerivative& st return true; } -bool LinearTimeInvariantSystem::initalize( +bool LinearTimeInvariantSystem::initialize( std::weak_ptr handler) { return true;