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

Position and velocity of nodes used to generate a Hermite spline. More...

#include <nodes_variables.h>

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

List of all members.

Classes

struct  NodeValueInfo
 Semantic information associated with a scalar node value. More...

Public Types

enum  Side { Start = 0, End }

Public Member Functions

void AddFinalBound (Dx deriv, const std::vector< int > &dimensions, const VectorXd &val)
 Restricts the last node in the spline.
void AddObserver (ObserverPtr const spline)
 Adds a dependent observer that gets notified when the nodes change.
void AddStartBound (Dx deriv, const std::vector< int > &dimensions, const VectorXd &val)
 Restricts the first node in the spline.
const std::vector< NodeGetBoundaryNodes (int poly_id) const
VecBound GetBounds () const override
int GetDim () const
const std::vector< NodeGetNodes () const
virtual std::vector
< NodeValueInfo
GetNodeValuesInfo (int opt_idx) const =0
 Node values affected by one specific optimization variable.
int GetOptIndex (const NodeValueInfo &nvi) const
 Index in the optimization vector for a specific nodes' pos/vel.
int GetPolynomialCount () const
VectorXd GetValues () const override
 Pure optimization variables that define the nodes.
void SetByLinearInterpolation (const VectorXd &initial_val, const VectorXd &final_val, double t_total)
 Sets nodes pos/vel equally spaced from initial to final position.
void SetVariables (const VectorXd &x) override
 Sets some node positions and velocity from the optimization variables.

Static Public Member Functions

static int GetNodeId (int poly_id, Side side)
 The node ID that belongs to a specific side of a specific polynomial.

Static Public Attributes

static const int NodeValueNotOptimized = -1

Protected Member Functions

 NodesVariables (const std::string &variable_name)
virtual ~NodesVariables ()

Protected Attributes

VecBound bounds_
 the bounds on the node values.
int n_dim_
std::vector< Nodenodes_

Private Member Functions

void AddBound (const NodeValueInfo &node_info, double value)
 Restricts a specific optimization variables.
void AddBounds (int node_id, Dx deriv, const std::vector< int > &dim, const VectorXd &values)
 Bounds a specific node variables.
void UpdateObservers () const
 Notifies the subscribed observers that the node values changes.

Private Attributes

std::vector< ObserverPtr > observers_

Detailed Description

Position and velocity of nodes used to generate a Hermite spline.

#### Four nodes defining a single spline (e.g. foot position in x-direction)

nodes.jpg

Instead of setting the polynomial coefficients directly, a third-order polynomial is also fully defined by the value and first-derivative of the start and end of the polynomial as well as the duration. This class holds these node values composed of position and velocity.

In the above image the nodes are defined by the scalar position and velocity values x0, x0d, ..., xT, xTd. By optimizing over these nodes, different spline shapes are generated. It is important to note that **not all node values must be optimized over**. We can fix specific node values in advance, or _one_ optimization variables can represent _multiple_ nodes values in the spline. This is exploited in the subclass NodesVariablesPhaseBased using _Phase-based End-effector Parameterization_.

Definition at line 71 of file nodes_variables.h.


Member Enumeration Documentation

Enumerator:
Start 
End 

Definition at line 159 of file nodes_variables.h.


Constructor & Destructor Documentation

towr::NodesVariables::NodesVariables ( const std::string &  variable_name) [protected]
Parameters:
n_dimThe number of dimensions (x,y,..) each node has.
variable_nameThe name of the variables in the optimization problem.

Definition at line 35 of file nodes_variables.cc.

virtual towr::NodesVariables::~NodesVariables ( ) [protected, virtual]

Member Function Documentation

void towr::NodesVariables::AddBound ( const NodeValueInfo node_info,
double  value 
) [private]

Restricts a specific optimization variables.

Parameters:
node_infoThe specs of the optimization variables to restrict.
valueThe value to set the bounds to.

Definition at line 162 of file nodes_variables.cc.

void towr::NodesVariables::AddBounds ( int  node_id,
Dx  deriv,
const std::vector< int > &  dim,
const VectorXd &  values 
) [private]

Bounds a specific node variables.

Parameters:
node_idThe ID of the node to bound.
derivThe derivative of the node to set.
dimThe dimension of the node to bound.
valuesThe values to set the bounds to.

Definition at line 153 of file nodes_variables.cc.

void towr::NodesVariables::AddFinalBound ( Dx  deriv,
const std::vector< int > &  dimensions,
const VectorXd &  val 
)

Restricts the last node in the spline.

Parameters:
derivWhich derivative (pos,vel,...) should be restricted.
dimensionsWhich dimensions (x,y,z) should be restricted.
valThe values the last node should be set to.

Definition at line 177 of file nodes_variables.cc.

void towr::NodesVariables::AddObserver ( ObserverPtr const  spline)

Adds a dependent observer that gets notified when the nodes change.

Parameters:
splineUsually a pointer to a spline which uses the node values.

Definition at line 82 of file nodes_variables.cc.

void towr::NodesVariables::AddStartBound ( Dx  deriv,
const std::vector< int > &  dimensions,
const VectorXd &  val 
)

Restricts the first node in the spline.

Parameters:
derivWhich derivative (pos,vel,...) should be restricted.
dimensionsWhich dimensions (x,y,z) should be restricted.
valThe values the fist node should be set to.

Definition at line 171 of file nodes_variables.cc.

const std::vector< Node > towr::NodesVariables::GetBoundaryNodes ( int  poly_id) const
Returns:
the two nodes that make up polynomial with "poly_id".

Definition at line 94 of file nodes_variables.cc.

NodesVariables::VecBound towr::NodesVariables::GetBounds ( ) const [override]
Returns:
the bounds on position and velocity of each node and dimension.

Definition at line 115 of file nodes_variables.cc.

Returns:
The dimensions (x,y,z) of every node.

Definition at line 103 of file nodes_variables.cc.

int towr::NodesVariables::GetNodeId ( int  poly_id,
Side  side 
) [static]

The node ID that belongs to a specific side of a specific polynomial.

Parameters:
poly_idThe ID of the polynomial within the spline.
sideThe side from which the node ID is required.

Definition at line 88 of file nodes_variables.cc.

const std::vector< Node > towr::NodesVariables::GetNodes ( ) const
Returns:
All the nodes that can be used to reconstruct the spline.

Definition at line 121 of file nodes_variables.cc.

virtual std::vector<NodeValueInfo> towr::NodesVariables::GetNodeValuesInfo ( int  opt_idx) const [pure virtual]

Node values affected by one specific optimization variable.

Parameters:
opt_idxThe index (=row) of the optimization variable.
Returns:
All node values affected by this optimization variable.

This function determines which node values are optimized over, and which nodes values are set by the same optimization variable.

Reverse of GetOptIndex().

Implemented in towr::NodesVariablesPhaseBased, and towr::NodesVariablesAll.

Index in the optimization vector for a specific nodes' pos/vel.

Parameters:
nviDescription of node value we want to know the index for.
Returns:
The position of this node value in the optimization variables.

Reverse of GetNodeInfoAtOptIndex().

Definition at line 41 of file nodes_variables.cc.

Returns:
the number of polynomials that can be built with these nodes.

Definition at line 109 of file nodes_variables.cc.

Eigen::VectorXd towr::NodesVariables::GetValues ( ) const [override]

Pure optimization variables that define the nodes.

Not all node position and velocities are independent or optimized over, so usually the number of optimization variables is less than all nodes' pos/vel.

See also:
GetNodeInfoAtOptIndex()

Definition at line 53 of file nodes_variables.cc.

void towr::NodesVariables::SetByLinearInterpolation ( const VectorXd &  initial_val,
const VectorXd &  final_val,
double  t_total 
)

Sets nodes pos/vel equally spaced from initial to final position.

Parameters:
initial_valvalue of the first node.
final_valvalue of the final node.
t_totalThe total duration to reach final node (to set velocities).

Definition at line 127 of file nodes_variables.cc.

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

Sets some node positions and velocity from the optimization variables.

Parameters:
xThe optimization variables.

Not all node position and velocities are independent or optimized over, so usually the number of optimization variables is less than all nodes pos/vel.

See also:
GetNodeValuesInfo()

Definition at line 65 of file nodes_variables.cc.

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

Notifies the subscribed observers that the node values changes.

Definition at line 75 of file nodes_variables.cc.


Member Data Documentation

VecBound towr::NodesVariables::bounds_ [protected]

the bounds on the node values.

Definition at line 214 of file nodes_variables.h.

Definition at line 216 of file nodes_variables.h.

std::vector<Node> towr::NodesVariables::nodes_ [protected]

Definition at line 215 of file nodes_variables.h.

Definition at line 115 of file nodes_variables.h.

std::vector<ObserverPtr> towr::NodesVariables::observers_ [private]

Definition at line 223 of file nodes_variables.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