diff --git a/CHANGELOG.md b/CHANGELOG.md index 4ca1c19ae9..0d25be00ac 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -14,6 +14,7 @@ All notable changes to this project are documented in this file. ### Fixed - Bug fix of `JointTorqueControlDevice` device (https://github.com/ami-iit/bipedal-locomotion-framework/pull/890) - Bug fix of `prepare_data` method calling in `joints-grid-position-tracking` (https://github.com/ami-iit/bipedal-locomotion-framework/pull/895) +- Fix the normal force limit constraint in the `CentroidalMPC` (https://github.com/ami-iit/bipedal-locomotion-framework/pull/898) ## [0.19.0] - 2024-09-06 ### Added diff --git a/src/ReducedModelControllers/src/CentroidalMPC.cpp b/src/ReducedModelControllers/src/CentroidalMPC.cpp index ef265ed464..81d05145ba 100644 --- a/src/ReducedModelControllers/src/CentroidalMPC.cpp +++ b/src/ReducedModelControllers/src/CentroidalMPC.cpp @@ -940,7 +940,7 @@ struct CentroidalMPC::Impl 0 <= casadi::MX::mtimes(casadi::MX::reshape(contact.orientation(Sl(), i), 3, 3), - corner.force(Sl(), i)(2))); + corner.force(Sl(), i))(2)); } } }