Skip to content

Commit

Permalink
use same freq for unit test as applicaiton to increase speed
Browse files Browse the repository at this point in the history
  • Loading branch information
mebbaid committed Nov 3, 2023
1 parent b5b4585 commit db43671
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
6 changes: 3 additions & 3 deletions src/ReducedModelControllers/src/StableCentroidalMPC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@ struct StableCentroidalMPC::Impl

struct StableConstants
{
const double alpha = 0.1;
const double k1 = 10.0;
const double alpha = 0.3;
const double k1 = 3.0;
};
StableConstants stableConstants;

Expand Down Expand Up @@ -790,7 +790,7 @@ struct StableCentroidalMPC::Impl
+ casadi::MX::mtimes(z2(Sl(), 0).T(), averageForce - u_adaptive)
<= 0.0);

this->opti.subject_to(casadi::MX::mtimes(angularMomentum(Sl(),1).T() , angularMomentum(Sl(),1)) <= this->stableConstants.alpha );
this->opti.subject_to(casadi::MX::mtimes(angularMomentum(Sl(),1).T() , angularMomentum(Sl(),1)) <= this->stableConstants.alpha );

for (const auto& [key, contact] : this->optiVariables.contacts)
{
Expand Down
6 changes: 3 additions & 3 deletions src/ReducedModelControllers/tests/StableCentroidalMPCTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,11 +88,11 @@ TEST_CASE("StableCentroidalMPC")
constexpr bool saveDataset = true;

using namespace std::chrono_literals;
constexpr std::chrono::nanoseconds dT = 100ms;
constexpr std::chrono::nanoseconds dT = 200ms;

std::shared_ptr<IParametersHandler> handler = std::make_shared<StdImplementation>();
handler->setParameter("sampling_time", dT);
handler->setParameter("time_horizon", 1s + 250ms);
handler->setParameter("time_horizon", 1s + 200ms);
handler->setParameter("number_of_maximum_contacts", 2);
handler->setParameter("number_of_slices", 1);
handler->setParameter("static_friction_coefficient", 0.33);
Expand Down Expand Up @@ -123,7 +123,7 @@ TEST_CASE("StableCentroidalMPC")
handler->setGroup("CONTACT_0", contact0Handler);
handler->setGroup("CONTACT_1", contact1Handler);

handler->setParameter("com_weight", std::vector<double>{1, 1, 200});
handler->setParameter("com_weight", std::vector<double>{1, 1, 1000});
handler->setParameter("contact_position_weight", 2e2);
handler->setParameter("force_rate_of_change_weight", std::vector<double>{10, 10, 10});
handler->setParameter("angular_momentum_weight", 1e2);
Expand Down

0 comments on commit db43671

Please sign in to comment.