Constraints evaluated at discretized times along a trajectory. More...
#include <time_discretization_constraint.h>

| Public Types | |
| 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 | |
| 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 | 
| Protected Member Functions | |
| int | GetNumberOfNodes () const | 
|  Protected Member Functions inherited from ifopt::ConstraintSet | |
| const VariablesPtr | GetVariables () const | 
| Protected Attributes | |
| VecTimes | dts_ | 
| times at which the constraint is evaluated.  More... | |
| Private Member Functions | |
| virtual void | UpdateBoundsAtInstance (double t, int k, VecBound &b) const =0 | 
| Sets upper/lower bound a specific time t, corresponding to node k.  More... | |
| virtual void | UpdateConstraintAtInstance (double t, int k, VectorXd &g) const =0 | 
| Sets the constraint value a specific time t, corresponding to node k.  More... | |
| virtual void | UpdateJacobianAtInstance (double t, int k, std::string var_set, Jacobian &jac) const =0 | 
| Sets Jacobian rows at a specific time t, corresponding to node k.  More... | |
| Additional Inherited Members | |
|  Static Public Attributes inherited from ifopt::Component | |
| static const int | kSpecifyLater | 
Constraints evaluated at discretized times along a trajectory.
Often one want to check the values of a specific constraint, e.g. RangeOfMotion, or DynamicConstraint at specific times t along the trajectory. This class is responsible for building the overall Jacobian from the individual Jacobians at each time instance.
Definition at line 50 of file time_discretization_constraint.h.
Definition at line 53 of file time_discretization_constraint.h.
| using towr::TimeDiscretizationConstraint::VecTimes = std::vector<double> | 
Definition at line 52 of file time_discretization_constraint.h.
| towr::TimeDiscretizationConstraint::TimeDiscretizationConstraint | ( | double | T, | 
| double | dt, | ||
| std::string | constraint_name | ||
| ) | 
Constructs a constraint for ifopt.
| T | The total duration of the trajectory. | 
| dt | The discretization interval at which each constraint is evaluated. | 
| constraint_name | The name of the constraint. | 
Definition at line 37 of file time_discretization_constraint.cc.
| towr::TimeDiscretizationConstraint::TimeDiscretizationConstraint | ( | const VecTimes & | dts, | 
| std::string | name | ||
| ) | 
construct a constraint for ifopt.
| dts | Time instances at which to evaluate the constraints. | 
| name | The name of the constraint. | 
Definition at line 52 of file time_discretization_constraint.cc.
| 
 | virtualdefault | 
| 
 | overridevirtual | 
Implements ifopt::ConstraintSet.
Definition at line 90 of file time_discretization_constraint.cc.
| 
 | overridevirtual | 
Implements ifopt::Component.
Definition at line 78 of file time_discretization_constraint.cc.
| 
 | protected | 
Definition at line 60 of file time_discretization_constraint.cc.
| 
 | overridevirtual | 
Implements ifopt::Component.
Definition at line 66 of file time_discretization_constraint.cc.
| 
 | privatepure 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 | 
Implemented in towr::DynamicConstraint, towr::RangeOfMotionConstraint, and towr::BaseMotionConstraint.
| 
 | privatepure 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 | 
Implemented in towr::DynamicConstraint, towr::RangeOfMotionConstraint, and towr::BaseMotionConstraint.
| 
 | privatepure 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. | 
Implemented in towr::DynamicConstraint, towr::RangeOfMotionConstraint, and towr::BaseMotionConstraint.
| 
 | protected | 
times at which the constraint is evaluated.
Definition at line 77 of file time_discretization_constraint.h.