43                                 bool is_first_phase_in_contact,
    47     :VariableSet(timings.size()-1, id::
EESchedule(ee))
    50   t_total_ = std::accumulate(timings.begin(), timings.end(), 0.0);
    65     spline->UpdatePolynomialDurations();
    73   for (
int i=0; i<x.rows(); ++i)
    82   for (
int i=0; i<GetRows(); ++i)
    90 PhaseDurations::VecBound
    95   for (
int i=0; i<GetRows(); ++i)
   114 PhaseDurations::Jacobian
   119   int n_dim = xd.rows();
   120   Eigen::MatrixXd jac = Eigen::MatrixXd::Zero(n_dim, GetRows());
   122   bool in_last_phase = (current_phase == 
durations_.size()-1);
   126     jac.col(current_phase) = dx_dT;
   128   for (
int phase=0; phase<current_phase; ++phase) {
   130     jac.col(phase) = -1*xd;
   135       jac.col(phase) -= dx_dT;
   141   return jac.sparseView(1.0, -1.0);
 
ifopt::Bounds phase_duration_bounds_
Base class to receive up-to-date values of the ContactSchedule. 
static std::string EESchedule(uint ee)
virtual VectorXd GetValues() const override
bool IsContactPhase(double t) const 
Whether the endeffector is in contact with the environment. 
VecBound GetBounds() const override
Jacobian GetJacobianOfPos(int phase, const VectorXd &dx_dT, const VectorXd &xd) const 
How a change in the phase durations affect the position of a spline. 
VecDurations GetPhaseDurations() const 
static int GetSegmentID(double t_global, const VecTimes &durations)
void UpdateObservers() const 
PhaseDurations(EndeffectorID ee, const VecDurations &initial_durations, bool is_first_phase_in_contact, double min_phase_duration, double max_phase_duration)
Constructs a variable set for a specific endeffector. 
std::vector< double > VecDurations
virtual void SetVariables(const VectorXd &x) override
Sets the phase durations from pure Eigen optimization variables. 
bool initial_contact_state_
true if first phase in contact 
void AddObserver(PhaseDurationsObserver *const spline)
Adds observer that is updated every time new variables are set. 
std::vector< PhaseDurationsObserver * > observers_