Skip to content

Commit

Permalink
Fix the normal force limit constraint in the CentroidalMPC (#898)
Browse files Browse the repository at this point in the history
  • Loading branch information
GiulioRomualdi authored Oct 1, 2024
1 parent 3f19707 commit da3d948
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 1 deletion.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion src/ReducedModelControllers/src/CentroidalMPC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
}
}
}
Expand Down

0 comments on commit da3d948

Please sign in to comment.