30 #ifndef TOWR_CONSTRAINTS_DYNAMIC_CONSTRAINT_H_ 31 #define TOWR_CONSTRAINTS_DYNAMIC_CONSTRAINT_H_ DynamicConstraint(const DynamicModel::Ptr &model, const Parameters ¶ms, const SplineHolder &spline_holder)
Construct a Dynamic constraint.
Ensure that the optimized motion complies with the system dynamics.
Eigen::Matrix< double, 6, 1 > Vector6d
Constraints evaluated at discretized times along a trajectory.
std::shared_ptr< NodeSpline > Ptr
void UpdateModel(double t) const
Updates the model with the current state and forces.
virtual void UpdateConstraintAtInstance(double t, int k, VectorXd &g) const override
Sets the constraint value a specific time t, corresponding to node k.
EulerConverter base_angular_
angular base state
NodeSpline::Ptr base_linear_
lin. base pos/vel/acc in world frame
virtual void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian &) const override
Sets Jacobian rows at a specific time t, corresponding to node k.
Holds pointers to fully constructed splines, that are linked to the optimization variables.
Converts Euler angles and derivatives to angular quantities.
std::shared_ptr< DynamicModel > Ptr
std::vector< NodeSpline::Ptr > ee_forces_
endeffector forces in world frame.
virtual void UpdateBoundsAtInstance(double t, int k, VecBound &bounds) const override
Sets upper/lower bound a specific time t, corresponding to node k.
std::vector< NodeSpline::Ptr > ee_motion_
endeffector position in world frame.
Holds the parameters to tune the optimization problem.
DynamicModel::Ptr model_
the dynamic model (e.g. Centroidal)
virtual ~DynamicConstraint()=default
int GetRow(int k, Dim6D dimension) const
The row in the overall constraint for this evaluation time.