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

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

#include <nodes.h>

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

List of all members.

Classes

struct  IndexInfo
 Holds information about the node the optimization index represents. 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
virtual VecBound GetBounds () const override
int GetDim () const
virtual std::vector< IndexInfoGetNodeInfoAtOptIndex (int idx) const =0
 The node information that the optimization index represents.
const std::vector< NodeGetNodes () const
int GetPolynomialCount () const
VectorXd GetValues () const override
int Index (const IndexInfo &node_info) const
 The index at which a specific node variable is stored.
int Index (int node_id, Dx deriv, int node_dim) const
void InitializeNodesTowardsGoal (const VectorXd &initial_pos, const VectorXd &final_pos, double t_total)
 Sets nodes pos/vel equally spaced from initial to final position.
void SetVariables (const VectorXd &x) override
 Sets the node position and velocity 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.

Protected Member Functions

void InitMembers (int n_nodes, int n_variables)
 initializes the member variables.
 Nodes (int n_dim, const std::string &variable_name)
virtual ~Nodes ()

Protected Attributes

VecBound bounds_
 the bounds on the node values.

Private Member Functions

void AddBound (const IndexInfo &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

int n_dim_
std::vector< Nodenodes_
std::vector< ObserverPtr > observers_

Detailed Description

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

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 way of specifying a polynomial is called "Hermite". These are the node values of position and velocity.

See also:
class CubicHermitePolynomial

Definition at line 52 of file nodes.h.


Member Enumeration Documentation

Enumerator:
Start 
End 

Definition at line 130 of file nodes.h.


Constructor & Destructor Documentation

towr::Nodes::Nodes ( int  n_dim,
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 36 of file nodes.cc.

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

Member Function Documentation

void towr::Nodes::AddBound ( const IndexInfo 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 195 of file nodes.cc.

void towr::Nodes::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 186 of file nodes.cc.

void towr::Nodes::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 212 of file nodes.cc.

void towr::Nodes::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 141 of file nodes.cc.

void towr::Nodes::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 204 of file nodes.cc.

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

Definition at line 153 of file nodes.cc.

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

Definition at line 174 of file nodes.cc.

int towr::Nodes::GetDim ( ) const
Returns:
The dimensions (x,y,z) of every node.

Definition at line 162 of file nodes.cc.

int towr::Nodes::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 147 of file nodes.cc.

std::vector< Nodes::IndexInfo > towr::Nodes::GetNodeInfoAtOptIndex ( int  idx) const [pure 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.

Implemented in towr::PhaseNodes, and towr::BaseNodes.

Definition at line 93 of file nodes.cc.

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

Definition at line 180 of file nodes.cc.

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

Definition at line 168 of file nodes.cc.

Eigen::VectorXd towr::Nodes::GetValues ( ) const [override]
Returns:
the stacked node position and velocity values.

Definition at line 112 of file nodes.cc.

int towr::Nodes::Index ( const IndexInfo node_info) const

The index at which a specific node variable is stored.

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

Definition at line 80 of file nodes.cc.

int towr::Nodes::Index ( int  node_id,
Dx  deriv,
int  node_dim 
) const

Definition at line 74 of file nodes.cc.

void towr::Nodes::InitializeNodesTowardsGoal ( const VectorXd &  initial_pos,
const VectorXd &  final_pos,
double  t_total 
)

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

Parameters:
initial_posThe position of the first node.
final_posThe position of the final node.
t_totalThe total duration to reach final node (to set velocities).

Definition at line 51 of file nodes.cc.

void towr::Nodes::InitMembers ( int  n_nodes,
int  n_variables 
) [protected]

initializes the member variables.

Parameters:
n_nodesThe number of nodes composing the spline.
n_variablesThe number of variables being optimized over.

Not every node value must be optimized, so n_variables can be different than 2*n_nodes*n_dim.

Definition at line 43 of file nodes.cc.

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

Sets the node position and velocity optimization variables.

Parameters:
xThe stacked variables.

Definition at line 124 of file nodes.cc.

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

Notifies the subscribed observers that the node values changes.

Definition at line 134 of file nodes.cc.


Member Data Documentation

VecBound towr::Nodes::bounds_ [protected]

the bounds on the node values.

Definition at line 176 of file nodes.h.

int towr::Nodes::n_dim_ [private]

Definition at line 190 of file nodes.h.

std::vector<Node> towr::Nodes::nodes_ [private]

Definition at line 189 of file nodes.h.

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

Definition at line 196 of file 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