Skip to content

Commit

Permalink
improve function name
Browse files Browse the repository at this point in the history
  • Loading branch information
mayataka committed Dec 20, 2022
1 parent 8dd1647 commit f4174ec
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
4 changes: 2 additions & 2 deletions ocs2_ipm/include/ocs2_ipm/IpmInitialization.h
Original file line number Diff line number Diff line change
Expand Up @@ -109,8 +109,8 @@ vector_t initializeTerminalSlackVariable(OptimalControlProblem& ocpDefinition, s
* @param initialSlackMarginRate : Additional margin rate of the initial slack variables. Corresponds to `slack_bound_frac` option of IPOPT.
* @return Initialized slack variable of the pre-jump state-only constraints.
*/
vector_t initializePreJumpSlackVariable(OptimalControlProblem& ocpDefinition, scalar_t time, const vector_t& state,
scalar_t initialSlackLowerBound, scalar_t initialSlackMarginRate);
vector_t initializeEventSlackVariable(OptimalControlProblem& ocpDefinition, scalar_t time, const vector_t& state,
scalar_t initialSlackLowerBound, scalar_t initialSlackMarginRate);

} // namespace ipm
} // namespace ocs2
4 changes: 2 additions & 2 deletions ocs2_ipm/src/IpmInitialization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,8 @@ vector_t initializeTerminalSlackVariable(OptimalControlProblem& ocpDefinition, s
return initializeSlackVariable(ineqConstraint, initialSlackLowerBound, initialSlackMarginRate);
}

vector_t initializePreJumpSlackVariable(OptimalControlProblem& ocpDefinition, scalar_t time, const vector_t& state,
scalar_t initialSlackLowerBound, scalar_t initialSlackMarginRate) {
vector_t initializeEventSlackVariable(OptimalControlProblem& ocpDefinition, scalar_t time, const vector_t& state,
scalar_t initialSlackLowerBound, scalar_t initialSlackMarginRate) {
if (ocpDefinition.preJumpInequalityConstraintPtr->empty()) {
return vector_t();
}
Expand Down
4 changes: 2 additions & 2 deletions ocs2_ipm/src/IpmSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -425,8 +425,8 @@ void IpmSolver::initializeSlackDualTrajectory(const std::vector<AnnotatedTime>&
std::tie(slackStateIneq[i], std::ignore) = ipm::fromMultiplierCollection(slackIneqTrajectory_.preJumps[cachedEventIndex]);
std::tie(dualStateIneq[i], std::ignore) = ipm::fromMultiplierCollection(dualIneqTrajectory_.preJumps[cachedEventIndex]);
} else {
slackStateIneq[i] = ipm::initializePreJumpSlackVariable(ocpDefinition, getIntervalStart(timeDiscretization[i]), x[i],
settings_.initialSlackLowerBound, settings_.initialSlackMarginRate);
slackStateIneq[i] = ipm::initializeEventSlackVariable(ocpDefinition, getIntervalStart(timeDiscretization[i]), x[i],
settings_.initialSlackLowerBound, settings_.initialSlackMarginRate);
dualStateIneq[i] =
ipm::initializeDualVariable(slackStateIneq[i], barrierParam, settings_.initialDualLowerBound, settings_.initialDualMarginRate);
}
Expand Down

0 comments on commit f4174ec

Please sign in to comment.