Ensure that the optimized motion complies with the system dynamics. More...
#include <dynamic_constraint.h>

| Public Member Functions | |
| DynamicConstraint (const DynamicModel::Ptr &model, const Parameters ¶ms, const SplineHolder &spline_holder) | |
| Construct a Dynamic constraint. | |
| virtual | ~DynamicConstraint () | 
| Private Member Functions | |
| int | GetRow (int k, Dim6D dimension) const | 
| The row in the overall constraint for this evaluation time. | |
| virtual void | UpdateBoundsAtInstance (double t, int k, VecBound &bounds) const override | 
| Sets upper/lower bound a specific time t, corresponding to node k. | |
| virtual void | UpdateConstraintAtInstance (double t, int k, VectorXd &g) const override | 
| Sets the constraint value a specific time t, corresponding to node k. | |
| virtual void | UpdateJacobianAtInstance (double t, int k, std::string, Jacobian &) const override | 
| Sets Jacobian rows at a specific time t, corresponding to node k. | |
| void | UpdateModel (double t) const | 
| Updates the model with the current state and forces. | |
| Private Attributes | |
| EulerConverter | base_angular_ | 
| angular base state | |
| NodeSpline::Ptr | base_linear_ | 
| lin. base pos/vel/acc in world frame | |
| std::vector< NodeSpline::Ptr > | ee_forces_ | 
| endeffector forces in world frame. | |
| std::vector< NodeSpline::Ptr > | ee_motion_ | 
| endeffector position in world frame. | |
| DynamicModel::Ptr | model_ | 
| the dynamic model (e.g. Centroidal) | |
Ensure that the optimized motion complies with the system dynamics.
At specific time instances along the trajecetory, this class checks the current value of the optimization variables and makes sure that the current robot state (pos,vel) and forces match the current acceleration defined by the system dynamics.
The physics-based acceleration is influenced by the robot state as xdd(t) = f(x(t), xd(t), f(t))
The constraint of the optimization variables w is then: g(t) = acc_spline(t) - xdd(t) = acc_spline(t) - xdd(x(t), xd(t), f(t)) = acc_spline(w) - xdd(w)
Definition at line 60 of file dynamic_constraint.h.
| towr::DynamicConstraint::DynamicConstraint | ( | const DynamicModel::Ptr & | model, | 
| const Parameters & | params, | ||
| const SplineHolder & | spline_holder | ||
| ) | 
Construct a Dynamic constraint.
| model | The system dynamics to enforce (e.g. centroidal, LIP, ...) | 
| evaluation_times | The times at which to check the system dynamics. | 
| spline_holder | A pointer to the current optimization variables. | 
Definition at line 37 of file dynamic_constraint.cc.
| virtual towr::DynamicConstraint::~DynamicConstraint | ( | ) |  [virtual] | 
| int towr::DynamicConstraint::GetRow | ( | int | k, | 
| Dim6D | dimension | ||
| ) | const  [private] | 
The row in the overall constraint for this evaluation time.
| k | The index of the constraint evaluation at t=k*dt. | 
| dimension | Which base acceleration dimension this constraint is for. | 
Definition at line 56 of file dynamic_constraint.cc.
| void towr::DynamicConstraint::UpdateBoundsAtInstance | ( | double | t, | 
| int | k, | ||
| VecBound & | b | ||
| ) | const  [override, private, virtual] | 
Sets upper/lower bound a specific time t, corresponding to node k.
| t | The time along the trajectory to set the bounds. | 
| k | The index of the time t, so t=k*dt | 
| in/out] | b The complete vector of bounds, for which the corresponding row must be set. | 
Implements towr::TimeDiscretizationConstraint.
Definition at line 69 of file dynamic_constraint.cc.
| void towr::DynamicConstraint::UpdateConstraintAtInstance | ( | double | t, | 
| int | k, | ||
| VectorXd & | g | ||
| ) | const  [override, private, virtual] | 
Sets the constraint value a specific time t, corresponding to node k.
| t | The time along the trajectory to set the constraint. | 
| k | The index of the time t, so t=k*dt | 
| in/out] | g The complete vector of constraint values, for which the corresponding row must be filled. | 
Implements towr::TimeDiscretizationConstraint.
Definition at line 62 of file dynamic_constraint.cc.
| void towr::DynamicConstraint::UpdateJacobianAtInstance | ( | double | t, | 
| int | k, | ||
| std::string | var_set, | ||
| Jacobian & | jac | ||
| ) | const  [override, private, virtual] | 
Sets Jacobian rows at a specific time t, corresponding to node k.
| t | The time along the trajcetory to set the bounds. | 
| k | The index of the time t, so t=k*dt | 
| var_set | The name of the ifopt variables currently being queried for. | 
| in/out] | jac The complete Jacobian, for which the corresponding row and columns must be set. | 
Implements towr::TimeDiscretizationConstraint.
Definition at line 76 of file dynamic_constraint.cc.
| void towr::DynamicConstraint::UpdateModel | ( | double | t | ) | const  [private] | 
Updates the model with the current state and forces.
| t | Time at which to query the state and force splines. | 
Definition at line 124 of file dynamic_constraint.cc.
angular base state
Definition at line 77 of file dynamic_constraint.h.
| NodeSpline::Ptr towr::DynamicConstraint::base_linear_  [private] | 
lin. base pos/vel/acc in world frame
Definition at line 76 of file dynamic_constraint.h.
| std::vector<NodeSpline::Ptr> towr::DynamicConstraint::ee_forces_  [private] | 
endeffector forces in world frame.
Definition at line 78 of file dynamic_constraint.h.
| std::vector<NodeSpline::Ptr> towr::DynamicConstraint::ee_motion_  [private] | 
endeffector position in world frame.
Definition at line 79 of file dynamic_constraint.h.
| DynamicModel::Ptr towr::DynamicConstraint::model_  [mutable, private] | 
the dynamic model (e.g. Centroidal)
Definition at line 81 of file dynamic_constraint.h.