Public Member Functions | Private Member Functions | Private Attributes
towr::PhaseDurations Class Reference

A variable set composed of the phase durations of an endeffector. More...

#include <phase_durations.h>

List of all members.

Public Member Functions

void AddObserver (PhaseDurationsObserver *const spline)
 Adds observer that is updated every time new variables are set.
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
VectorXd GetValues () const override
bool IsContactPhase (double t) const
 Whether the endeffector is in contact with the environment.
 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.
void SetVariables (const VectorXd &x) override
 Sets the phase durations from pure Eigen optimization variables.
virtual ~PhaseDurations ()

Private Member Functions

void UpdateObservers () const

Private Attributes

VecDurations durations_
bool initial_contact_state_
 true if first phase in contact
std::vector
< PhaseDurationsObserver * > 
observers_
ifopt::Bounds phase_duration_bounds_
double t_total_

Detailed Description

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.


Constructor & Destructor Documentation

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.

Parameters:
eeThe endeffector ID which these durations apply to.
initial_durationsInitial values for the optimization variables.
min_phase_durationThe minimum allowable time for one phase.
max_phase_durationThe maximum allowable time for one phase.

Definition at line 41 of file phase_durations.cc.


Member Function Documentation

Adds observer that is updated every time new variables are set.

Parameters:
splineA pointer to a Hermite spline using the durations.

Definition at line 56 of file phase_durations.cc.

PhaseDurations::VecBound towr::PhaseDurations::GetBounds ( ) const [override]
Returns:
The maximum and minimum time each phase is allowed to take.

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.

Parameters:
phaseThe current phase the spline is in at time t.
dx_dTThe derivative of the spline position w.r.t the phase durations T.
xdThe velocity of the spline at the current time t.
Returns:
A pxn dimensional Jacobian where: p: number of dimensions of the spline (e.g. x,y,z) n: number of phase durations in this class that are optimized over.

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
Returns:
The durations (stance, swing, ...) for each phase of this foot.

Definition at line 114 of file phase_durations.cc.

Eigen::VectorXd towr::PhaseDurations::GetValues ( ) const [override]
Returns:
The optimization variables (phase durations [s]).

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.

Parameters:
tglobal time along the trajectory.

Definition at line 120 of file phase_durations.cc.

void towr::PhaseDurations::SetVariables ( const VectorXd &  x) [override]

Sets the phase durations from pure Eigen optimization variables.

Definition at line 80 of file phase_durations.cc.

void towr::PhaseDurations::UpdateObservers ( ) const [private]

Definition at line 62 of file phase_durations.cc.


Member Data Documentation

VecDurations towr::PhaseDurations::durations_ [private]

Definition at line 121 of file phase_durations.h.

true if first phase in contact

Definition at line 124 of file phase_durations.h.

Definition at line 127 of file phase_durations.h.

Definition at line 125 of file phase_durations.h.

Definition at line 123 of file phase_durations.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