Ensure that the optimized motion complies with the system dynamics. More...
#include <dynamic_constraint.h>
Public Types | |
using | Vector6d = Eigen::Matrix< double, 6, 1 > |
Public Types inherited from towr::TimeDiscretizationConstraint | |
using | Bounds = ifopt::Bounds |
using | VecTimes = std::vector< double > |
Public Types inherited from ifopt::ConstraintSet | |
typedef std::shared_ptr< ConstraintSet > | Ptr |
typedef Composite::Ptr | VariablesPtr |
Public Types inherited from ifopt::Component | |
typedef Eigen::SparseMatrix< double, Eigen::RowMajor > | Jacobian |
typedef std::shared_ptr< Component > | Ptr |
typedef std::vector< Bounds > | VecBound |
typedef Eigen::VectorXd | VectorXd |
Public Member Functions | |
DynamicConstraint (const DynamicModel::Ptr &model, double T, double dt, const SplineHolder &spline_holder) | |
Construct a Dynamic constraint. More... | |
virtual | ~DynamicConstraint ()=default |
Public Member Functions inherited from towr::TimeDiscretizationConstraint | |
void | FillJacobianBlock (std::string var_set, Jacobian &) const override |
VecBound | GetBounds () const override |
Eigen::VectorXd | GetValues () const override |
TimeDiscretizationConstraint (double T, double dt, std::string constraint_name) | |
Constructs a constraint for ifopt. More... | |
TimeDiscretizationConstraint (const VecTimes &dts, std::string name) | |
construct a constraint for ifopt. More... | |
virtual | ~TimeDiscretizationConstraint ()=default |
Public Member Functions inherited from ifopt::ConstraintSet | |
ConstraintSet (int n_constraints, const std::string &name) | |
Jacobian | GetJacobian () const final |
void | LinkWithVariables (const VariablesPtr &x) |
virtual | ~ConstraintSet ()=default |
Public Member Functions inherited from ifopt::Component | |
Component (int num_rows, const std::string &name) | |
std::string | GetName () const |
int | GetRows () const |
virtual void | Print (double tolerance, int &index_start) const |
void | SetRows (int num_rows) |
virtual | ~Component ()=default |
Private Member Functions | |
int | GetRow (int k, Dim6D dimension) const |
The row in the overall constraint for this evaluation time. More... | |
void | UpdateBoundsAtInstance (double t, int k, VecBound &bounds) const override |
Sets upper/lower bound a specific time t, corresponding to node k. More... | |
void | UpdateConstraintAtInstance (double t, int k, VectorXd &g) const override |
Sets the constraint value a specific time t, corresponding to node k. More... | |
void | UpdateJacobianAtInstance (double t, int k, std::string, Jacobian &) const override |
Sets Jacobian rows at a specific time t, corresponding to node k. More... | |
void | UpdateModel (double t) const |
Updates the model with the current state and forces. More... | |
Private Attributes | |
EulerConverter | base_angular_ |
angular base state More... | |
NodeSpline::Ptr | base_linear_ |
lin. base pos/vel/acc in world frame More... | |
std::vector< NodeSpline::Ptr > | ee_forces_ |
endeffector forces in world frame. More... | |
std::vector< NodeSpline::Ptr > | ee_motion_ |
endeffector position in world frame. More... | |
DynamicModel::Ptr | model_ |
the dynamic model (e.g. Centroidal) More... | |
Additional Inherited Members | |
Static Public Attributes inherited from ifopt::Component | |
static const int | kSpecifyLater |
Protected Member Functions inherited from towr::TimeDiscretizationConstraint | |
int | GetNumberOfNodes () const |
Protected Member Functions inherited from ifopt::ConstraintSet | |
const VariablesPtr | GetVariables () const |
Protected Attributes inherited from towr::TimeDiscretizationConstraint | |
VecTimes | dts_ |
times at which the constraint is evaluated. More... | |
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 63 of file dynamic_constraint.h.
using towr::DynamicConstraint::Vector6d = Eigen::Matrix<double, 6, 1> |
Definition at line 65 of file dynamic_constraint.h.
towr::DynamicConstraint::DynamicConstraint | ( | const DynamicModel::Ptr & | model, |
double | T, | ||
double | dt, | ||
const SplineHolder & | spline_holder | ||
) |
Construct a Dynamic constraint.
model | The system dynamics to enforce (e.g. centroidal, LIP, ...) |
T | The total duration of the optimization. |
dt | the discretization intervall at which to enforce constraints. |
spline_holder | A pointer to the current optimization variables. |
Definition at line 37 of file dynamic_constraint.cc.
|
virtualdefault |
|
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 54 of file dynamic_constraint.cc.
|
overrideprivatevirtual |
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 |
Implements towr::TimeDiscretizationConstraint.
Definition at line 67 of file dynamic_constraint.cc.
|
overrideprivatevirtual |
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 |
Implements towr::TimeDiscretizationConstraint.
Definition at line 60 of file dynamic_constraint.cc.
|
overrideprivatevirtual |
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. |
Implements towr::TimeDiscretizationConstraint.
Definition at line 74 of file dynamic_constraint.cc.
|
private |
Updates the model with the current state and forces.
t | Time at which to query the state and force splines. |
Definition at line 120 of file dynamic_constraint.cc.
|
private |
angular base state
Definition at line 81 of file dynamic_constraint.h.
|
private |
lin. base pos/vel/acc in world frame
Definition at line 80 of file dynamic_constraint.h.
|
private |
endeffector forces in world frame.
Definition at line 82 of file dynamic_constraint.h.
|
private |
endeffector position in world frame.
Definition at line 83 of file dynamic_constraint.h.
|
mutableprivate |
the dynamic model (e.g. Centroidal)
Definition at line 85 of file dynamic_constraint.h.