A variable set composed of the phase durations of an endeffector. More...
#include <phase_durations.h>
Public Types | |
using | EndeffectorID = uint |
using | Ptr = std::shared_ptr< PhaseDurations > |
using | VecDurations = std::vector< double > |
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 | AddObserver (PhaseDurationsObserver *const spline) |
Adds observer that is updated every time new variables are set. More... | |
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. More... | |
VecDurations | GetPhaseDurations () const |
VectorXd | GetValues () const override |
bool | IsContactPhase (double t) const |
Whether the endeffector is in contact with the environment. More... | |
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. More... | |
void | SetVariables (const VectorXd &x) override |
Sets the phase durations from pure Eigen optimization variables. More... | |
virtual | ~PhaseDurations ()=default |
Public Member Functions inherited from ifopt::VariableSet | |
Jacobian | GetJacobian () const final |
VariableSet (int n_var, const std::string &name) | |
virtual | ~VariableSet ()=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 |
Private Member Functions | |
void | UpdateObservers () const |
Private Attributes | |
VecDurations | durations_ |
bool | initial_contact_state_ |
true if first phase in contact More... | |
std::vector< PhaseDurationsObserver * > | observers_ |
ifopt::Bounds | phase_duration_bounds_ |
double | t_total_ |
Additional Inherited Members | |
Static Public Attributes inherited from ifopt::Component | |
static const int | kSpecifyLater |
A variable set composed of the phase durations of an endeffector.
This class holds the current variables determining the alternating swing- and stance durations of one foot. These durations are then used in the Spline together with NodeVariables to construct foot motions and forces.
See this explanation: https://youtu.be/KhWuLvb934g?t=788
Definition at line 50 of file phase_durations.h.
using towr::PhaseDurations::EndeffectorID = uint |
Definition at line 54 of file phase_durations.h.
using towr::PhaseDurations::Ptr = std::shared_ptr<PhaseDurations> |
Definition at line 52 of file phase_durations.h.
using towr::PhaseDurations::VecDurations = std::vector<double> |
Definition at line 53 of file phase_durations.h.
towr::PhaseDurations::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.
ee | The endeffector ID which these durations apply to. |
initial_durations | Initial values for the optimization variables. |
min_phase_duration | The minimum allowable time for one phase. |
max_phase_duration | The maximum allowable time for one phase. |
Definition at line 41 of file phase_durations.cc.
|
virtualdefault |
void towr::PhaseDurations::AddObserver | ( | PhaseDurationsObserver *const | spline | ) |
Adds observer that is updated every time new variables are set.
spline | A pointer to a Hermite spline using the durations. |
Definition at line 56 of file phase_durations.cc.
|
overridevirtual |
Implements ifopt::Component.
Definition at line 103 of file phase_durations.cc.
PhaseDurations::Jacobian towr::PhaseDurations::GetJacobianOfPos | ( | int | phase, |
const VectorXd & | dx_dT, | ||
const VectorXd & | xd | ||
) | const |
How a change in the phase durations affect the position of a spline.
phase | The current phase the spline is in at time t. |
dx_dT | The derivative of the spline position w.r.t the phase durations T. |
xd | The velocity of the spline at the current time t. |
This method is related to constructing a cubic-Hermite spline with these phase durations. Leaving the node values unchanged, the shape of the spline can also be changed by expanding or compressing the individual polynomials through the duration. This method quantifies the sensitivity of the spline position on these durations.
Definition at line 127 of file phase_durations.cc.
PhaseDurations::VecDurations towr::PhaseDurations::GetPhaseDurations | ( | ) | const |
Definition at line 114 of file phase_durations.cc.
|
overridevirtual |
Implements ifopt::Component.
Definition at line 69 of file phase_durations.cc.
bool towr::PhaseDurations::IsContactPhase | ( | double | t | ) | const |
Whether the endeffector is in contact with the environment.
t | global time along the trajectory. |
Definition at line 120 of file phase_durations.cc.
|
overridevirtual |
Sets the phase durations from pure Eigen optimization variables.
Implements ifopt::Component.
Definition at line 80 of file phase_durations.cc.
|
private |
Definition at line 62 of file phase_durations.cc.
|
private |
Definition at line 121 of file phase_durations.h.
|
private |
true if first phase in contact
Definition at line 124 of file phase_durations.h.
|
private |
Definition at line 127 of file phase_durations.h.
|
private |
Definition at line 125 of file phase_durations.h.
|
private |
Definition at line 123 of file phase_durations.h.