Skip to content

Commit 551ef20

Browse files
committed
update pull request
1 parent e5a5c00 commit 551ef20

File tree

7 files changed

+12
-16
lines changed

7 files changed

+12
-16
lines changed

ocs2_ipm/src/IpmHelpers.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ scalar_t fractionToBoundaryStepSize(const vector_t& v, const vector_t& dv, scala
110110

111111
const vector_t invFractionToBoundary = (-1.0 / marginRate) * dv.cwiseQuotient(v);
112112
const auto alpha = invFractionToBoundary.maxCoeff();
113-
return alpha > 0.0? std::min(1.0 / alpha, 1.0): 1.0;
113+
return alpha > 0.0 ? std::min(1.0 / alpha, 1.0) : 1.0;
114114
}
115115

116116
} // namespace ipm

ocs2_robotic_examples/ocs2_cartpole_ros/launch/multiplot.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<launch>
22
<arg name="observation_config" default="$(find ocs2_cartpole)/config/multiplot/mpc_observation.xml" />
3-
<arg name="metrics_config" default="$(find ocs2_cartpole)/config/multiplot/zero_velocity.xml" />
3+
<arg name="metrics_config" default="$(find ocs2_cartpole)/config/multiplot/mpc_metrics.xml" />
44

55
<!-- Launch RQT Multi-plot -->
66
<node name="mpc_observation" pkg="rqt_multiplot" type="rqt_multiplot"

ocs2_robotic_examples/ocs2_legged_robot/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ if(cmake_clang_tools_FOUND)
122122
TARGETS ${PROJECT_NAME}
123123
SOURCE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/src ${CMAKE_CURRENT_SOURCE_DIR}/include ${CMAKE_CURRENT_SOURCE_DIR}/test
124124
CT_HEADER_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/include
125-
CF_WERROR
125+
CF_FIX
126126
)
127127
endif(cmake_clang_tools_FOUND)
128128

ocs2_robotic_examples/ocs2_legged_robot/config/mpc/task.info

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ ipm
5454
ipmIteration 1
5555
deltaTol 1e-4
5656
g_max 10.0
57-
g_min 1e-4
57+
g_min 1e-6
5858
computeLagrangeMultipliers true
5959
printSolverStatistics true
6060
printSolverStatus false

ocs2_robotic_examples/ocs2_legged_robot/include/ocs2_legged_robot/LeggedRobotInterface.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ class LeggedRobotInterface final : public RobotInterface {
111111
mpc::Settings mpcSettings_;
112112
sqp::Settings sqpSettings_;
113113
ipm::Settings ipmSettings_;
114-
bool useHardFrictionConeConstraint_;
114+
const bool useHardFrictionConeConstraint_;
115115

116116
std::unique_ptr<PinocchioInterface> pinocchioInterfacePtr_;
117117
CentroidalModelInfo centroidalModelInfo_;

ocs2_robotic_examples/ocs2_legged_robot/src/LeggedRobotInterface.cpp

Lines changed: 6 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,8 @@ namespace legged_robot {
6565
/******************************************************************************************************/
6666
/******************************************************************************************************/
6767
LeggedRobotInterface::LeggedRobotInterface(const std::string& taskFile, const std::string& urdfFile, const std::string& referenceFile,
68-
bool useHardFrictionConeConstraint) {
68+
bool useHardFrictionConeConstraint)
69+
: useHardFrictionConeConstraint_(useHardFrictionConeConstraint) {
6970
// check that task file exists
7071
boost::filesystem::path taskFilePath(taskFile);
7172
if (boost::filesystem::exists(taskFilePath)) {
@@ -93,12 +94,11 @@ LeggedRobotInterface::LeggedRobotInterface(const std::string& taskFile, const st
9394

9495
// load setting from loading file
9596
modelSettings_ = loadModelSettings(taskFile, "model_settings", verbose);
96-
ddpSettings_ = ddp::loadSettings(taskFile, "ddp", verbose);
9797
mpcSettings_ = mpc::loadSettings(taskFile, "mpc", verbose);
98-
rolloutSettings_ = rollout::loadSettings(taskFile, "rollout", verbose);
98+
ddpSettings_ = ddp::loadSettings(taskFile, "ddp", verbose);
9999
sqpSettings_ = sqp::loadSettings(taskFile, "sqp", verbose);
100100
ipmSettings_ = ipm::loadSettings(taskFile, "ipm", verbose);
101-
useHardFrictionConeConstraint_ = useHardFrictionConeConstraint;
101+
rolloutSettings_ = rollout::loadSettings(taskFile, "rollout", verbose);
102102

103103
// OptimalConrolProblem
104104
setupOptimalConrolProblem(taskFile, urdfFile, referenceFile, verbose);
@@ -329,13 +329,9 @@ std::unique_ptr<StateInputConstraint> LeggedRobotInterface::getFrictionConeConst
329329
/******************************************************************************************************/
330330
std::unique_ptr<StateInputCost> LeggedRobotInterface::getFrictionConeSoftConstraint(
331331
size_t contactPointIndex, scalar_t frictionCoefficient, const RelaxedBarrierPenalty::Config& barrierPenaltyConfig) {
332-
FrictionConeConstraint::Config frictionConeConConfig(frictionCoefficient);
333-
auto frictionConeConstraintPtr = std::make_unique<FrictionConeConstraint>(*referenceManagerPtr_, std::move(frictionConeConConfig),
334-
contactPointIndex, centroidalModelInfo_);
335-
336332
auto penalty = std::make_unique<RelaxedBarrierPenalty>(barrierPenaltyConfig);
337-
338-
return std::make_unique<StateInputSoftConstraint>(std::move(frictionConeConstraintPtr), std::move(penalty));
333+
return std::make_unique<StateInputSoftConstraint>(getFrictionConeConstraint(contactPointIndex, frictionCoefficient),
334+
std::make_unique<RelaxedBarrierPenalty>(barrierPenaltyConfig));
339335
}
340336

341337
/******************************************************************************************************/

ocs2_robotic_examples/ocs2_legged_robot_ros/src/LeggedRobotIpmMpcNode.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ int main(int argc, char** argv) {
7272
mpc.getSolverPtr()->setReferenceManager(rosReferenceManagerPtr);
7373
mpc.getSolverPtr()->addSynchronizedModule(gaitReceiverPtr);
7474

75-
// observer for zero velocity constraints (only add this for debugging as it slows down the solver)
75+
// observer for friction cone constraints (only add this for debugging as it slows down the solver)
7676
if (multiplot) {
7777
auto createStateInputBoundsObserver = [&](const std::string& termName) {
7878
const ocs2::scalar_array_t observingTimePoints{0.0};

0 commit comments

Comments
 (0)