@@ -64,7 +64,9 @@ namespace legged_robot {
64
64
/* *****************************************************************************************************/
65
65
/* *****************************************************************************************************/
66
66
/* *****************************************************************************************************/
67
- LeggedRobotInterface::LeggedRobotInterface (const std::string& taskFile, const std::string& urdfFile, const std::string& referenceFile) {
67
+ LeggedRobotInterface::LeggedRobotInterface (const std::string& taskFile, const std::string& urdfFile, const std::string& referenceFile,
68
+ bool useHardFrictionConeConstraint)
69
+ : useHardFrictionConeConstraint_(useHardFrictionConeConstraint) {
68
70
// check that task file exists
69
71
boost::filesystem::path taskFilePath (taskFile);
70
72
if (boost::filesystem::exists (taskFilePath)) {
@@ -92,10 +94,11 @@ LeggedRobotInterface::LeggedRobotInterface(const std::string& taskFile, const st
92
94
93
95
// load setting from loading file
94
96
modelSettings_ = loadModelSettings (taskFile, " model_settings" , verbose);
95
- ddpSettings_ = ddp::loadSettings (taskFile, " ddp" , verbose);
96
97
mpcSettings_ = mpc::loadSettings (taskFile, " mpc" , verbose);
97
- rolloutSettings_ = rollout ::loadSettings (taskFile, " rollout " , verbose);
98
+ ddpSettings_ = ddp ::loadSettings (taskFile, " ddp " , verbose);
98
99
sqpSettings_ = sqp::loadSettings (taskFile, " sqp" , verbose);
100
+ ipmSettings_ = ipm::loadSettings (taskFile, " ipm" , verbose);
101
+ rolloutSettings_ = rollout::loadSettings (taskFile, " rollout" , verbose);
99
102
100
103
// OptimalConrolProblem
101
104
setupOptimalConrolProblem (taskFile, urdfFile, referenceFile, verbose);
@@ -174,8 +177,12 @@ void LeggedRobotInterface::setupOptimalConrolProblem(const std::string& taskFile
174
177
modelSettings_.recompileLibrariesCppAd , modelSettings_.verboseCppAd ));
175
178
}
176
179
177
- problemPtr_->softConstraintPtr ->add (footName + " _frictionCone" ,
178
- getFrictionConeConstraint (i, frictionCoefficient, barrierPenaltyConfig));
180
+ if (useHardFrictionConeConstraint_) {
181
+ problemPtr_->inequalityConstraintPtr ->add (footName + " _frictionCone" , getFrictionConeConstraint (i, frictionCoefficient));
182
+ } else {
183
+ problemPtr_->softConstraintPtr ->add (footName + " _frictionCone" ,
184
+ getFrictionConeSoftConstraint (i, frictionCoefficient, barrierPenaltyConfig));
185
+ }
179
186
problemPtr_->equalityConstraintPtr ->add (footName + " _zeroForce" , getZeroForceConstraint (i));
180
187
problemPtr_->equalityConstraintPtr ->add (footName + " _zeroVelocity" ,
181
188
getZeroVelocityConstraint (*eeKinematicsPtr, i, useAnalyticalGradientsConstraints));
@@ -310,15 +317,20 @@ std::pair<scalar_t, RelaxedBarrierPenalty::Config> LeggedRobotInterface::loadFri
310
317
/* *****************************************************************************************************/
311
318
/* *****************************************************************************************************/
312
319
/* *****************************************************************************************************/
313
- std::unique_ptr<StateInputCost > LeggedRobotInterface::getFrictionConeConstraint (size_t contactPointIndex, scalar_t frictionCoefficient ,
314
- const RelaxedBarrierPenalty::Config& barrierPenaltyConfig ) {
320
+ std::unique_ptr<StateInputConstraint > LeggedRobotInterface::getFrictionConeConstraint (size_t contactPointIndex,
321
+ scalar_t frictionCoefficient ) {
315
322
FrictionConeConstraint::Config frictionConeConConfig (frictionCoefficient);
316
- auto frictionConeConstraintPtr = std::make_unique<FrictionConeConstraint>(*referenceManagerPtr_, std::move (frictionConeConConfig),
317
- contactPointIndex, centroidalModelInfo_);
318
-
319
- auto penalty = std::make_unique<RelaxedBarrierPenalty>(barrierPenaltyConfig);
323
+ return std::make_unique<FrictionConeConstraint>(*referenceManagerPtr_, std::move (frictionConeConConfig), contactPointIndex,
324
+ centroidalModelInfo_);
325
+ }
320
326
321
- return std::make_unique<StateInputSoftConstraint>(std::move (frictionConeConstraintPtr), std::move (penalty));
327
+ /* *****************************************************************************************************/
328
+ /* *****************************************************************************************************/
329
+ /* *****************************************************************************************************/
330
+ std::unique_ptr<StateInputCost> LeggedRobotInterface::getFrictionConeSoftConstraint (
331
+ size_t contactPointIndex, scalar_t frictionCoefficient, const RelaxedBarrierPenalty::Config& barrierPenaltyConfig) {
332
+ return std::make_unique<StateInputSoftConstraint>(getFrictionConeConstraint (contactPointIndex, frictionCoefficient),
333
+ std::make_unique<RelaxedBarrierPenalty>(barrierPenaltyConfig));
322
334
}
323
335
324
336
/* *****************************************************************************************************/
0 commit comments