Go to the documentation of this file.
25 #ifndef SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_EDGES_COLLOCATION_EDGES_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_EDGES_COLLOCATION_EDGES_H_
42 class QuadratureCollocationDynamicsOnly :
public Edge<>
45 using Ptr = std::shared_ptr<QuadratureCollocationDynamicsOnly>;
46 using UPtr = std::unique_ptr<QuadratureCollocationDynamicsOnly>;
49 :
Edge<>(5 + quadrature->getNumIntermediateStates() + quadrature->getNumIntermediateControls()),
86 bool isLinear()
const override {
return false; }
122 std::vector<const Eigen::VectorXd*>
_x1_points;
123 std::vector<const Eigen::VectorXd*>
_u1_points;
124 const Eigen::VectorXd*
_x2 =
nullptr;
125 const Eigen::VectorXd*
_u2 =
nullptr;
136 using Ptr = std::shared_ptr<QuadratureCollocationEdge>;
137 using UPtr = std::unique_ptr<QuadratureCollocationEdge>;
141 bool eval_intermediate_constr,
int k)
142 :
MixedEdge<>(5 + quadrature->getNumIntermediateStates() + quadrature->getNumIntermediateControls()),
153 assert(quadrature->isIntermediateControlSubjectToOptim());
330 _stage_cost->computeIntegralStateControlTerm(
_k,
x, u, result.head(1));
346 assert(idx == result.size());
385 const Eigen::VectorXd*
_x2 =
nullptr;
386 const Eigen::VectorXd*
_u2 =
nullptr;
397 using Ptr = std::shared_ptr<CompressedCollocationEdge>;
398 using UPtr = std::unique_ptr<CompressedCollocationEdge>;
418 bool isLinear()
const override {
return false; }
438 assert(!collocation->isIntermediateControlSubjectToOptim() && collocation->isSupportingCompressedStatesMode());
459 using Ptr = std::shared_ptr<CompressedCollocationMultipleControlsEdge>;
460 using UPtr = std::unique_ptr<CompressedCollocationMultipleControlsEdge>;
463 :
Edge<>(5 + quadrature->getNumIntermediatePoints()),
468 assert(quadrature->isIntermediateControlSubjectToOptim());
502 bool isLinear()
const override {
return false; }
554 using Ptr = std::shared_ptr<ConstControlCombinedCompressedCollocationEdge>;
555 using UPtr = std::unique_ptr<ConstControlCombinedCompressedCollocationEdge>;
569 int x_dim =
_dynamics->getStateDimension();
710 assert(!quadrature->isIntermediateControlSubjectToOptim() && quadrature->isSupportingCompressedStatesMode());
723 int num_interm_states =
_collocation->getNumIntermediatePoints();
778 using Ptr = std::shared_ptr<CombinedCompressedCollocationEdge>;
779 using UPtr = std::unique_ptr<CombinedCompressedCollocationEdge>;
793 int x_dim =
_dynamics->getStateDimension();
852 integrand, obj_values);
862 _stage_eq->computeIntegralStateControlTerm(
_k,
x, u, result);
890 integrand, ineq_values);
939 assert(!quadrature->isIntermediateControlSubjectToOptim() && quadrature->isSupportingCompressedStatesMode());
955 int num_interm_states =
_collocation->getNumIntermediatePoints();
1012 using Ptr = std::shared_ptr<CombinedCompressedCollocationMultipleControlsEdge>;
1013 using UPtr = std::unique_ptr<CombinedCompressedCollocationMultipleControlsEdge>;
1028 assert(quadrature->isIntermediateControlSubjectToOptim());
1033 int x_dim =
_dynamics->getStateDimension();
1106 integrand, obj_values);
1116 _stage_eq->computeIntegralStateControlTerm(
_k,
x, u, result);
1144 integrand, ineq_values);
1198 int num_interm_states =
_collocation->getNumIntermediatePoints();
1263 using Ptr = std::shared_ptr<UncompressedCollocationEdge>;
1264 using UPtr = std::unique_ptr<UncompressedCollocationEdge>;
1267 :
Edge<>(5 + quadrature->getNumIntermediatePoints() * (1 + (
int)quadrature->isIntermediateControlSubjectToOptim())),
1298 if (
_collocation->isIntermediateControlSubjectToOptim())
1320 bool isLinear()
const override {
return false; }
1395 using Ptr = std::shared_ptr<CombinedUncompressedCollocationEdge>;
1396 using UPtr = std::unique_ptr<CombinedUncompressedCollocationEdge>;
1401 :
MixedEdge<>(5 + quadrature->getNumIntermediatePoints() * (1 + (
int)quadrature->isIntermediateControlSubjectToOptim())),
1448 if (
_collocation->isIntermediateControlSubjectToOptim())
1511 integrand, obj_values);
1525 _stage_eq->computeIntegralStateControlTerm(
_k,
x, u, result);
1556 integrand, ineq_values);
1563 for (
int i = 0; i <
_collocation->getNumIntermediatePoints(); ++i)
1580 int num_interm_states =
_collocation->getNumIntermediatePoints();
1641 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_STRUCTURED_OCP_EDGES_COLLOCATION_EDGES_H_
bool isObjectiveLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
std::vector< Eigen::VectorXd * > _intermediate_u
Eigen::VectorXd _dynamics_quadrature
bool isObjectiveLeastSquaresForm() const override
StageCost::Ptr _stage_cost
#define PRINT_WARNING_COND_NAMED(cond, msg)
std::vector< Eigen::VectorXd * > _intermediate_u
void precompute() override
void clearInternalBuffer()
Eigen::VectorXd _quadrature_values
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
SystemDynamicsInterface::Ptr _dynamics
UncompressedCollocationEdge(SystemDynamicsInterface::Ptr dynamics, QuadratureCollocationInterface::Ptr quadrature)
virtual ~CombinedCompressedCollocationMultipleControlsEdge()
int getDimension() const override
Return number of elements/values/components stored in this vertex.
int getObjectiveDimension() const override
std::unique_ptr< CompressedCollocationEdge > UPtr
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
bool _intermediate_u_internal_buf
bool isObjectiveLeastSquaresForm() const override
QuadratureCollocationInterface::Ptr _collocation
void clearInternalBuffer()
std::vector< Eigen::VectorXd * > _intermediate_u
void setCollocationMethod(QuadratureCollocationInterface::Ptr collocation)
int _num_intermediate_points
const Eigen::VectorXd & upperBound() const
Read-access to the underlying upper bound vector.
bool isObjectiveLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
std::shared_ptr< CompressedCollocationMultipleControlsEdge > Ptr
std::vector< Eigen::VectorXd * > _intermediate_x
QuadratureCollocationEdge(SystemDynamicsInterface::Ptr dynamics, QuadratureCollocationInterface::Ptr quadrature, StageCost::Ptr stage_cost, StageEqualityConstraint::Ptr stage_eq, StageInequalityConstraint::Ptr stage_ineq, bool eval_intermediate_constr, int k)
std::vector< const Eigen::VectorXd * > _u1_points
QuadratureCollocationInterface::Ptr _collocation
bool hasFiniteUpperBound(int idx) const override
Check if finite upper bound for a single component is provided.
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
QuadratureCollocationInterface::Ptr _collocation
bool isInequalityLinear() const override
std::shared_ptr< StageInequalityConstraint > Ptr
void precompute() override
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
std::vector< Eigen::VectorXd * > _intermediate_x
const Eigen::VectorXd * _u2
CompressedCollocationMultipleControlsEdge(SystemDynamicsInterface::Ptr dynamics, QuadratureCollocationInterface::Ptr quadrature)
std::shared_ptr< UncompressedCollocationEdge > Ptr
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
bool hasFiniteLowerBound(int idx) const override
Check if finite lower bound for a single component is provided.
VertexContainer _vertices
Vertex container.
std::vector< Eigen::VectorXd * > _intermediate_u
int getInequalityDimension() const override
int getInequalityDimension() const override
bool isEqualityLinear() const override
SystemDynamicsInterface::Ptr _dynamics
StageEqualityConstraint::Ptr _stage_eq
SystemDynamicsInterface::Ptr _dynamics
const Eigen::VectorXd * _x2
StageInequalityConstraint::Ptr _stage_ineq
const VertexContainer _vertices
Vertex container.
std::shared_ptr< ConstControlCombinedCompressedCollocationEdge > Ptr
std::unique_ptr< CombinedCompressedCollocationMultipleControlsEdge > UPtr
CompressedCollocationEdge(SystemDynamicsInterface::Ptr dynamics, VectorVertex &x1, VectorVertex &u1, ScalarVertex &dt, VectorVertex &u2, VectorVertex &x2)
void configureIntegrand()
int _num_intermediate_points
Eigen::VectorXd _dynamics_quadrature
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
bool isEqualityLinear() const override
virtual ~CompressedCollocationMultipleControlsEdge()
std::shared_ptr< StageCost > Ptr
SystemDynamicsInterface::Ptr _dynamics
int getEqualityDimension() const override
const Eigen::VectorXd & values() const
Read-access to the underlying value vector.
const Eigen::VectorXd * _x2
void activateIntermediateConstraints()
StageCost::Ptr _stage_cost
const Eigen::VectorXd * _u2
void precompute() override
ConstControlCombinedCompressedCollocationEdge(SystemDynamicsInterface::Ptr dynamics, StageCost::Ptr stage_cost, StageEqualityConstraint::Ptr stage_eq, StageInequalityConstraint::Ptr stage_ineq, bool eval_intermediate_constr, int k, VectorVertex &x1, VectorVertex &u1, ScalarVertex &dt, VectorVertex &x2)
int getEqualityDimension() const override
SystemDynamicsInterface::Ptr _dynamics
Eigen::VectorXd _dynamics_quadrature
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
QuadratureCollocationInterface::Ptr _collocation
std::unique_ptr< CompressedCollocationMultipleControlsEdge > UPtr
StageEqualityConstraint::Ptr _stage_eq
bool _eval_intermediate_constr
int getInequalityDimension() const override
CombinedCompressedCollocationMultipleControlsEdge(SystemDynamicsInterface::Ptr dynamics, QuadratureCollocationInterface::Ptr quadrature, StageCost::Ptr stage_cost, StageEqualityConstraint::Ptr stage_eq, StageInequalityConstraint::Ptr stage_ineq, bool eval_intermediate_constr, int k)
bool isInequalityLinear() const override
int getNumberFiniteUpperBounds(bool unfixed_only) const override
Get number of finite upper bounds.
void activateIntermediateConstraints()
bool isEqualityLinear() const override
StageInequalityConstraint::Ptr _stage_ineq
Eigen::VectorXd _midpoint_error
StageEqualityConstraint::Ptr _stage_eq
StageEqualityConstraint::Ptr _stage_eq
SystemDynamicsInterface::Ptr _dynamics
StageCost::Ptr _stage_cost
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
StageEqualityConstraint::Ptr _stage_eq
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
int getEqualityDimension() const override
std::function< void(const Eigen::VectorXd &, const Eigen::VectorXd &, Eigen::Ref< Eigen::VectorXd >)> _integrand
std::shared_ptr< CombinedCompressedCollocationMultipleControlsEdge > Ptr
int _num_intermediate_points
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
SystemDynamicsInterface::Ptr _dynamics
void clearInternalBuffer()
std::shared_ptr< QuadratureCollocationDynamicsOnly > Ptr
bool isObjectiveLeastSquaresForm() const override
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
bool _eval_intermediate_constr
int getObjectiveDimension() const override
void setCollocationMethod(QuadratureCollocationInterface::Ptr quadrature)
StageInequalityConstraint::Ptr _stage_ineq
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
StageInequalityConstraint::Ptr _stage_ineq
bool isEqualityLinear() const override
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
int getEqualityDimension() const override
void precompute() override
bool _eval_intermediate_constr
StageInequalityConstraint::Ptr _stage_ineq
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
std::shared_ptr< SystemDynamicsInterface > Ptr
QuadratureCollocationInterface::Ptr _collocation
std::vector< Eigen::VectorXd * > _intermediate_x
int getInequalityDimension() const override
virtual ~CombinedCompressedCollocationEdge()
std::vector< Eigen::VectorXd * > _intermediate_x
CombinedCompressedCollocationEdge(SystemDynamicsInterface::Ptr dynamics, StageCost::Ptr stage_cost, StageEqualityConstraint::Ptr stage_eq, StageInequalityConstraint::Ptr stage_ineq, bool eval_intermediate_constr, int k, VectorVertex &x1, VectorVertex &u1, ScalarVertex &dt, VectorVertex &u2, VectorVertex &x2)
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
void activateIntermediateConstraints()
std::unique_ptr< ConstControlCombinedCompressedCollocationEdge > UPtr
bool isObjectiveLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
bool isInequalityLinear() const override
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
SystemDynamicsInterface::Ptr _dynamics
virtual ~ConstControlCombinedCompressedCollocationEdge()
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Eigen::VectorXd _dynamics_quadrature
A matrix or vector expression mapping an existing expression.
int getInequalityDimension() const override
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
std::vector< const Eigen::VectorXd * > _u1_points
const double & value() const
Get underlying value.
std::vector< Eigen::VectorXd * > _intermediate_x
bool isObjectiveLeastSquaresForm() const override
virtual ~CombinedUncompressedCollocationEdge()
CombinedUncompressedCollocationEdge(SystemDynamicsInterface::Ptr dynamics, QuadratureCollocationInterface::Ptr quadrature, StageCost::Ptr stage_cost, StageEqualityConstraint::Ptr stage_eq, StageInequalityConstraint::Ptr stage_ineq, bool eval_intermediate_constr, int k)
std::vector< Eigen::VectorXd * > _intermediate_u
VertexContainer _vertices
Vertex container.
bool isInequalityLinear() const override
int getEqualityDimension() const override
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
std::shared_ptr< CompressedCollocationEdge > Ptr
QuadratureCollocationDynamicsOnly(SystemDynamicsInterface::Ptr dynamics, QuadratureCollocationInterface::Ptr quadrature)
void precompute() override
std::unique_ptr< QuadratureCollocationEdge > UPtr
std::vector< const Eigen::VectorXd * > _x1_points
Eigen::VectorXd _dynamics_quadrature
std::shared_ptr< QuadratureCollocationEdge > Ptr
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
int _num_intermediate_points
QuadratureCollocationInterface::Ptr _collocation
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Vertex implementation for scalar values.
virtual ~QuadratureCollocationEdge()=default
void clearInternalBuffer()
int getObjectiveDimension() const override
std::shared_ptr< CombinedCompressedCollocationEdge > Ptr
int getNumberFiniteLowerBounds(bool unfixed_only) const override
Get number of finite lower bounds.
bool _eval_intermediate_constr
std::vector< Eigen::VectorXd * > _intermediate_x
Eigen::VectorXd _midpoint_error
void activateIntermediateConstraints()
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
const Eigen::VectorXd & lowerBound() const
Read-access to the underlying lower bound vector.
Templated base edge class that stores an arbitary number of value.
void setCollocationMethod(QuadratureCollocationInterface::Ptr quadrature)
QuadratureCollocationInterface::Ptr _collocation
std::shared_ptr< QuadratureCollocationInterface > Ptr
int getObjectiveDimension() const override
std::unique_ptr< UncompressedCollocationEdge > UPtr
bool _eval_intermediate_constr
Vertex implementation that stores an Eigen::VectorXd (dynamic dimension)
SystemDynamicsInterface::Ptr _dynamics
std::unique_ptr< QuadratureCollocationDynamicsOnly > UPtr
virtual ~QuadratureCollocationDynamicsOnly()=default
std::vector< const Eigen::VectorXd * > _x1_points
QuadratureCollocationInterface::Ptr _collocation
bool _intermediate_u_internal_buf
StageCost::Ptr _stage_cost
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
std::shared_ptr< StageEqualityConstraint > Ptr
StageCost::Ptr _stage_cost
QuadratureCollocationInterface::Ptr _collocation
std::unique_ptr< CombinedCompressedCollocationEdge > UPtr
bool isObjectiveLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
bool isInequalityLinear() const override
bool isObjectiveLeastSquaresForm() const override
bool isObjectiveLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
int getObjectiveDimension() const override
bool isEqualityLinear() const override
const VertexContainer _vertices
Vertex container.
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:39