30 #ifndef TOWR_VARIABLES_CONTACT_SCHEDULE_H_ 31 #define TOWR_VARIABLES_CONTACT_SCHEDULE_H_ 52 using Ptr = std::shared_ptr<PhaseDurations>;
66 bool is_first_phase_in_contact,
67 double min_phase_duration,
68 double max_phase_duration);
ifopt::Bounds phase_duration_bounds_
Base class to receive up-to-date values of the ContactSchedule.
VectorXd GetValues() const override
bool IsContactPhase(double t) const
Whether the endeffector is in contact with the environment.
VecBound GetBounds() const override
virtual ~PhaseDurations()=default
std::shared_ptr< Component > Ptr
A variable set composed of the phase durations of an endeffector.
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
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.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
std::vector< double > VecDurations
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< Bounds > VecBound
std::vector< PhaseDurationsObserver * > observers_