31 bool NlpFunctions::update(
int n,
double t, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, ReferenceTrajectoryInterface* sref,
32 bool single_dt,
const Eigen::VectorXd& x0,
const std::vector<double>& dts,
const DiscretizationGridInterface* grid)
34 bool dimension_modified =
false;
42 dimension_modified |=
final_stage_constraints->update(
n, t, xref, uref, sref, single_dt, x0,
final_stage_cost,
stage_preprocessor, dts, grid);
44 return dimension_modified;
51 else if (
x_lb.size() != x_dim)
56 else if (
x_ub.size() != x_dim)
61 else if (
u_lb.size() != u_dim)
66 else if (
u_ub.size() != u_dim)
79 edges.push_back(edge);
88 edges.push_back(edge);
97 edges.push_back(edge);
106 edges.push_back(edge);
112 using Edge = BinaryVectorVertexEdge<StageFunction, &StageFunction::computeNonIntegralStateControlTerm>;
113 Edge::Ptr edge = std::make_shared<Edge>(dim, k, stage_fun, xk, uk,
false,
false);
114 edges.push_back(edge);
120 using Edge = TernaryVectorScalarVertexEdge<StageFunction, &StageFunction::computeNonIntegralControlDeviationTerm>;
121 Edge::Ptr edge = std::make_shared<Edge>(dim, k, stage_fun, uk, u_prev, u_prev_dt,
false,
false);
122 edges.push_back(edge);
128 using Edge = TernaryVectorScalarVertexEdge<StageFunction, &StageFunction::computeNonIntegralStateControlDtTerm>;
129 Edge::Ptr edge = std::make_shared<Edge>(dim, k, stage_fun, xk, uk, dt,
false,
false);
130 edges.push_back(edge);
135 ScalarVertex& u_prev_dt, std::vector<BaseEdge::Ptr>& cost_edges,
136 std::vector<BaseEdge::Ptr>& eq_edges, std::vector<BaseEdge::Ptr>& ineq_edges)
153 std::vector<BaseEdge::Ptr>& cost_edges, std::vector<BaseEdge::Ptr>& eq_edges,
154 std::vector<BaseEdge::Ptr>& ineq_edges)
158 int dim =
stage_cost->getNonIntegralControlDeviationTermDimension(
n);
162 Edge::Ptr edge = std::make_shared<Edge>(dim,
n, *
stage_cost, u_ref, u_prev, u_prev_dt,
false,
false);
163 cost_edges.push_back(edge);
173 eq_edges.push_back(edge);
181 using Edge = TernaryVectorScalarVertexEdge<StageFunction, &StageFunction::computeNonIntegralControlDeviationTerm>;
183 ineq_edges.push_back(edge);
195 using Edge = UnaryVectorVertexEdge<StageFunction, &StageFunction::computeNonIntegralStateTerm>;