Classes | Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
towr::NodesVariables Class Referenceabstract

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

#include <nodes_variables.h>

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

Classes

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

Public Types

using ObserverPtr = NodesObserver *
 
using Ptr = std::shared_ptr< NodesVariables >
 
enum  Side { Start =0, End }
 
using VecDurations = std::vector< double >
 
- Public Types inherited from ifopt::Component
typedef Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
 
typedef std::shared_ptr< ComponentPtr
 
typedef std::vector< BoundsVecBound
 
typedef Eigen::VectorXd VectorXd
 

Public Member Functions

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

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. More...
 

Static Public Attributes

static const int NodeValueNotOptimized = -1
 
- Static Public Attributes inherited from ifopt::Component
static const int kSpecifyLater
 

Protected Member Functions

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

Protected Attributes

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

Private Member Functions

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

Private Attributes

std::vector< ObserverPtrobservers_
 

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 Typedef Documentation

Definition at line 75 of file nodes_variables.h.

using towr::NodesVariables::Ptr = std::shared_ptr<NodesVariables>

Definition at line 73 of file nodes_variables.h.

using towr::NodesVariables::VecDurations = std::vector<double>

Definition at line 74 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 ( )
protectedvirtualdefault

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
overridevirtual
Returns
the bounds on position and velocity of each node and dimension.

Implements ifopt::Component.

Definition at line 115 of file nodes_variables.cc.

int towr::NodesVariables::GetDim ( ) const
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.

int towr::NodesVariables::GetOptIndex ( const NodeValueInfo nvi) const

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.

int towr::NodesVariables::GetPolynomialCount ( ) const
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
overridevirtual

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()

Implements ifopt::Component.

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)
overridevirtual

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()

Implements ifopt::Component.

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.

int towr::NodesVariables::n_dim_
protected

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.

const int towr::NodesVariables::NodeValueNotOptimized = -1
static

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 Sat Apr 13 2019 02:28:00