Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions
towr::TimeDiscretizationConstraint Class Reference

Constraints evaluated at discretized times along a trajectory. More...

#include <time_discretization_constraint.h>

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

List of all members.

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.
 TimeDiscretizationConstraint (const VecTimes &dts, std::string name)
 construct a constraint for ifopt.
virtual ~TimeDiscretizationConstraint ()

Protected Member Functions

int GetNumberOfNodes () const

Protected Attributes

VecTimes dts_
 times at which the constraint is evaluated.

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.
virtual void UpdateConstraintAtInstance (double t, int k, VectorXd &g) const =0
 Sets the constraint value a specific time t, corresponding to node k.
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.

Detailed Description

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.


Constructor & Destructor Documentation

towr::TimeDiscretizationConstraint::TimeDiscretizationConstraint ( double  T,
double  dt,
std::string  constraint_name 
)

Constructs a constraint for ifopt.

Parameters:
TThe total duration of the trajectory.
dtThe discretization interval at which each constraint is evaluated.
constraint_nameThe 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.

Parameters:
dtsTime instances at which to evaluate the constraints.
nameThe name of the constraint.

Definition at line 52 of file time_discretization_constraint.cc.


Member Function Documentation

void towr::TimeDiscretizationConstraint::FillJacobianBlock ( std::string  var_set,
Jacobian &  jac 
) const [override]

Definition at line 90 of file time_discretization_constraint.cc.

TimeDiscretizationConstraint::VecBound towr::TimeDiscretizationConstraint::GetBounds ( ) const [override]

Definition at line 78 of file time_discretization_constraint.cc.

Definition at line 60 of file time_discretization_constraint.cc.

TimeDiscretizationConstraint::VectorXd towr::TimeDiscretizationConstraint::GetValues ( ) const [override]

Definition at line 66 of file time_discretization_constraint.cc.

virtual void towr::TimeDiscretizationConstraint::UpdateBoundsAtInstance ( double  t,
int  k,
VecBound &  b 
) const [private, pure virtual]

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
in/out]b The complete vector of bounds, for which the corresponding row must be set.

Implemented in towr::DynamicConstraint, towr::RangeOfMotionConstraint, and towr::BaseMotionConstraint.

virtual void towr::TimeDiscretizationConstraint::UpdateConstraintAtInstance ( double  t,
int  k,
VectorXd &  g 
) const [private, pure virtual]

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
in/out]g The complete vector of constraint values, for which the corresponding row must be filled.

Implemented in towr::DynamicConstraint, towr::RangeOfMotionConstraint, and towr::BaseMotionConstraint.

virtual void towr::TimeDiscretizationConstraint::UpdateJacobianAtInstance ( double  t,
int  k,
std::string  var_set,
Jacobian &  jac 
) const [private, pure virtual]

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.
in/out]jac The complete Jacobian, for which the corresponding row and columns must be set.

Implemented in towr::DynamicConstraint, towr::RangeOfMotionConstraint, and towr::BaseMotionConstraint.


Member Data Documentation

times at which the constraint is evaluated.

Definition at line 77 of file time_discretization_constraint.h.


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


towr
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 15 2019 02:42:32