Classes | Public Types | Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
towr::PhaseNodes Class Reference

Nodes that are associated to either swing or stance phases. More...

#include <phase_nodes.h>

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

List of all members.

Classes

struct  PolyInfo
 Holds semantic information each polynomial in spline. More...

Public Types

enum  Type { Force, Motion }

Public Member Functions

virtual VecDurations ConvertPhaseToPolyDurations (const VecDurations &phase_durations) const
 Converts durations of swing and stance phases to polynomial durations.
virtual double GetDerivativeOfPolyDurationWrtPhaseDuration (int polynomial_id) const
 How a change in the phase duration affects the polynomial duration.
NodeIds GetIndicesOfNonConstantNodes () const
 The indices of those nodes that don't belong to a constant phase.
int GetNodeIDAtStartOfPhase (int phase) const
virtual std::vector< IndexInfoGetNodeInfoAtOptIndex (int idx) const override
 The node information that the optimization index represents.
virtual int GetNumberOfPrevPolynomialsInPhase (int polynomial_id) const
 How many polynomials in the current phase come before.
int GetPhase (int node_id) const
Eigen::Vector3d GetValueAtStartOfPhase (int phase) const
virtual bool IsConstantNode (int node_id) const
 node is constant if either left or right polynomial belongs to a constant phase.
virtual bool IsInConstantPhase (int polynomial_id) const
 Is the polynomial constant, so not changing the value.
 PhaseNodes (int phase_count, bool in_contact_start, const std::string &var_name, int n_polys_in_changing_phase, Type type)
 Constructs a variable set of node variables.
virtual ~PhaseNodes ()

Private Member Functions

std::vector< int > GetAdjacentPolyIds (int node_id) const
int GetPolyIDAtStartOfPhase (int phase) const
void SetBoundsEEForce ()
 Sets the bounds on the node variables to model foot forces.
void SetBoundsEEMotion ()
 Sets the bounds on the node variables to model foot motions.

Static Private Member Functions

static std::map< OptNodeIs,
NodeIds > 
GetOptNodeToNodeMappings (const std::vector< PolyInfo > &)

Private Attributes

std::map< OptNodeIs, NodeIds > optnode_to_node_
std::vector< PolyInfopolynomial_info_

Detailed Description

Nodes that are associated to either swing or stance phases.

In the node values, not every node is an optimization variable, but two consecutive nodes forming a e.g. stance position spline belong to the same optimization variable. This is because a foot in stance cannot move (or a force in flight must be zero). This makes the number of optimization variables less than the total node values.

Definition at line 46 of file phase_nodes.h.


Member Enumeration Documentation

Enumerator:
Force 
Motion 

Definition at line 52 of file phase_nodes.h.


Constructor & Destructor Documentation

towr::PhaseNodes::PhaseNodes ( int  phase_count,
bool  in_contact_start,
const std::string &  var_name,
int  n_polys_in_changing_phase,
Type  type 
)

Constructs a variable set of node variables.

Parameters:
phase_countThe number of phases (swing, stance) to represent.
in_contact__startWhether the first node belongs to a stance phase.
var_nameThe name given to this set of optimization variables.
n_polys_in_changing_phaseHow many polynomials should be used to paramerize each non-constant phase.
typeThese nodes represent either force evolution or foot motions.

Definition at line 61 of file phase_nodes.cc.

virtual towr::PhaseNodes::~PhaseNodes ( ) [virtual]

Member Function Documentation

PhaseNodes::VecDurations towr::PhaseNodes::ConvertPhaseToPolyDurations ( const VecDurations &  phase_durations) const [virtual]

Converts durations of swing and stance phases to polynomial durations.

Parameters:
phase_durationsThe durations of alternating swing and stance phases.
Returns:
The durations of each polynomial, where multiple polynomials can be used to represent one phase.

Definition at line 84 of file phase_nodes.cc.

std::vector< int > towr::PhaseNodes::GetAdjacentPolyIds ( int  node_id) const [private]

Definition at line 219 of file phase_nodes.cc.

double towr::PhaseNodes::GetDerivativeOfPolyDurationWrtPhaseDuration ( int  polynomial_id) const [virtual]

How a change in the phase duration affects the polynomial duration.

Parameters:
polynomial_idThe ID of the polynomial within the spline.

If a phase is represented by multiple (3) equally timed polynomials, then T_poly = 1/3 * T_phase. The derivative of T_poly is then 1/3.

Definition at line 97 of file phase_nodes.cc.

PhaseNodes::NodeIds towr::PhaseNodes::GetIndicesOfNonConstantNodes ( ) const

The indices of those nodes that don't belong to a constant phase.

For forces nodes these are the stance phases (can produce force), and for feet these are the swing phases (can move end-effector).

Definition at line 175 of file phase_nodes.cc.

Returns:
the ID of the first node in the phase.

Definition at line 212 of file phase_nodes.cc.

std::vector< PhaseNodes::IndexInfo > towr::PhaseNodes::GetNodeInfoAtOptIndex ( int  idx) const [override, virtual]

The node information that the optimization index represents.

Parameters:
idxThe index (=row) of the node optimization variable.
Returns:
Semantic information on what that optimization variables means.

One optimization variables can also represent multiple nodes in the spline if they are always equal (e.g. constant phases). This is why this function returns a vector.

Implements towr::Nodes.

Definition at line 131 of file phase_nodes.cc.

int towr::PhaseNodes::GetNumberOfPrevPolynomialsInPhase ( int  polynomial_id) const [virtual]

How many polynomials in the current phase come before.

Parameters:
polynomial_idThe ID of the polynomial within the spline.

If a phase is represented by multiple (3) polynomials, and the current polynomial corresponds to the third one in the phase, then 2 polynomials come before it.

Definition at line 104 of file phase_nodes.cc.

std::map< PhaseNodes::OptNodeIs, PhaseNodes::NodeIds > towr::PhaseNodes::GetOptNodeToNodeMappings ( const std::vector< PolyInfo > &  polynomial_info) [static, private]

Definition at line 110 of file phase_nodes.cc.

int towr::PhaseNodes::GetPhase ( int  node_id) const
Returns:
The phase ID belonging to node with node_id.

Only makes sense if left and right polynomial belong to same phase.

Definition at line 187 of file phase_nodes.cc.

int towr::PhaseNodes::GetPolyIDAtStartOfPhase ( int  phase) const [private]
Returns:
the ID of the polynomial at the start of phase phase.

Definition at line 196 of file phase_nodes.cc.

Eigen::Vector3d towr::PhaseNodes::GetValueAtStartOfPhase ( int  phase) const
Returns:
the value of the first node of the phase.

Definition at line 205 of file phase_nodes.cc.

bool towr::PhaseNodes::IsConstantNode ( int  node_id) const [virtual]

node is constant if either left or right polynomial belongs to a constant phase.

Definition at line 155 of file phase_nodes.cc.

bool towr::PhaseNodes::IsInConstantPhase ( int  polynomial_id) const [virtual]

Is the polynomial constant, so not changing the value.

Parameters:
polynomial_idThe ID of the polynomial within the spline.

Definition at line 169 of file phase_nodes.cc.

Sets the bounds on the node variables to model foot forces.

For this the force for nodes representing swing-phases is set to zero.

Definition at line 267 of file phase_nodes.cc.

Sets the bounds on the node variables to model foot motions.

For this the velocity of the stance nodes is bounds to zero.

Definition at line 237 of file phase_nodes.cc.


Member Data Documentation

std::map<OptNodeIs, NodeIds > towr::PhaseNodes::optnode_to_node_ [private]

Definition at line 155 of file phase_nodes.h.

Definition at line 150 of file phase_nodes.h.


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


towr_core
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 9 2018 03:12:44