Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
towr::DynamicConstraint Class Reference

Ensure that the optimized motion complies with the system dynamics. More...

#include <dynamic_constraint.h>

Inheritance diagram for towr::DynamicConstraint:
Inheritance graph
[legend]

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 Member Functions

 DynamicConstraint (const DynamicModel::Ptr &model, const Parameters &params, 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
 

Private Member Functions

int GetRow (int k, Dim6D dimension) const
 The row in the overall constraint for this evaluation time. More...
 
virtual void UpdateBoundsAtInstance (double t, int k, VecBound &bounds) const override
 Sets upper/lower bound a specific time t, corresponding to node k. More...
 
virtual void UpdateConstraintAtInstance (double t, int k, VectorXd &g) const override
 Sets the constraint value a specific time t, corresponding to node k. More...
 
virtual 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::Ptree_forces_
 endeffector forces in world frame. More...
 
std::vector< NodeSpline::Ptree_motion_
 endeffector position in world frame. More...
 
DynamicModel::Ptr model_
 the dynamic model (e.g. Centroidal) More...
 

Additional Inherited Members

- Protected Member Functions inherited from towr::TimeDiscretizationConstraint
int GetNumberOfNodes () const
 
- Protected Attributes inherited from towr::TimeDiscretizationConstraint
VecTimes dts_
 times at which the constraint is evaluated. More...
 

Detailed Description

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.

Member Typedef Documentation

using towr::DynamicConstraint::Vector6d = Eigen::Matrix<double, 6, 1>

Definition at line 62 of file dynamic_constraint.h.

Constructor & Destructor Documentation

towr::DynamicConstraint::DynamicConstraint ( const DynamicModel::Ptr model,
const Parameters params,
const SplineHolder spline_holder 
)

Construct a Dynamic constraint.

Parameters
modelThe system dynamics to enforce (e.g. centroidal, LIP, ...)
evaluation_timesThe times at which to check the system dynamics.
spline_holderA pointer to the current optimization variables.

Definition at line 37 of file dynamic_constraint.cc.

virtual towr::DynamicConstraint::~DynamicConstraint ( )
virtualdefault

Member Function Documentation

int towr::DynamicConstraint::GetRow ( int  k,
Dim6D  dimension 
) const
private

The row in the overall constraint for this evaluation time.

Parameters
kThe index of the constraint evaluation at t=k*dt.
dimensionWhich base acceleration dimension this constraint is for.
Returns
The constraint index in the overall dynamic constraint.

Definition at line 56 of file dynamic_constraint.cc.

void towr::DynamicConstraint::UpdateBoundsAtInstance ( double  t,
int  k,
VecBound &  b 
) const
overrideprivatevirtual

Sets upper/lower bound a specific time t, corresponding to node k.

Parameters
tThe time along the trajectory to set the bounds.
kThe index of the time t, so t=k*dt

Implements towr::TimeDiscretizationConstraint.

Definition at line 69 of file dynamic_constraint.cc.

void towr::DynamicConstraint::UpdateConstraintAtInstance ( double  t,
int  k,
VectorXd g 
) const
overrideprivatevirtual

Sets the constraint value a specific time t, corresponding to node k.

Parameters
tThe time along the trajectory to set the constraint.
kThe index of the time t, so t=k*dt

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
overrideprivatevirtual

Sets Jacobian rows at a specific time t, corresponding to node k.

Parameters
tThe time along the trajcetory to set the bounds.
kThe index of the time t, so t=k*dt
var_setThe name of the ifopt variables currently being queried for.

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.

Parameters
tTime at which to query the state and force splines.

Definition at line 124 of file dynamic_constraint.cc.

Member Data Documentation

EulerConverter towr::DynamicConstraint::base_angular_
private

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_
mutableprivate

the dynamic model (e.g. Centroidal)

Definition at line 81 of file dynamic_constraint.h.


The documentation for this class was generated from the following files:


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sun Apr 8 2018 02:18:53