Position and velocity of nodes used to generate a Hermite spline. More...
#include <nodes_variables.h>
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< Component > | Ptr |
typedef std::vector< Bounds > | VecBound |
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< Node > | GetBoundaryNodes (int poly_id) const |
VecBound | GetBounds () const override |
int | GetDim () const |
const std::vector< Node > | GetNodes () const |
virtual std::vector< NodeValueInfo > | GetNodeValuesInfo (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< Node > | nodes_ |
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< ObserverPtr > | observers_ |
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 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.
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.
Enumerator | |
---|---|
Start | |
End |
Definition at line 159 of file nodes_variables.h.
|
protected |
n_dim | The number of dimensions (x,y,..) each node has. |
variable_name | The name of the variables in the optimization problem. |
Definition at line 35 of file nodes_variables.cc.
|
protectedvirtualdefault |
|
private |
Restricts a specific optimization variables.
node_info | The specs of the optimization variables to restrict. |
value | The value to set the bounds to. |
Definition at line 162 of file nodes_variables.cc.
|
private |
Bounds a specific node variables.
node_id | The ID of the node to bound. |
deriv | The derivative of the node to set. |
dim | The dimension of the node to bound. |
values | The 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.
deriv | Which derivative (pos,vel,...) should be restricted. |
dimensions | Which dimensions (x,y,z) should be restricted. |
val | The 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.
spline | Usually 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.
deriv | Which derivative (pos,vel,...) should be restricted. |
dimensions | Which dimensions (x,y,z) should be restricted. |
val | The 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 |
Definition at line 94 of file nodes_variables.cc.
|
overridevirtual |
Implements ifopt::Component.
Definition at line 115 of file nodes_variables.cc.
int towr::NodesVariables::GetDim | ( | ) | const |
Definition at line 103 of file nodes_variables.cc.
|
static |
The node ID that belongs to a specific side of a specific polynomial.
poly_id | The ID of the polynomial within the spline. |
side | The 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 |
Definition at line 121 of file nodes_variables.cc.
|
pure virtual |
Node values affected by one specific optimization variable.
opt_idx | The index (=row) of the 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.
nvi | Description of node value we want to know the index for. |
Reverse of GetNodeInfoAtOptIndex().
Definition at line 41 of file nodes_variables.cc.
int towr::NodesVariables::GetPolynomialCount | ( | ) | const |
Definition at line 109 of file nodes_variables.cc.
|
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.
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.
initial_val | value of the first node. |
final_val | value of the final node. |
t_total | The total duration to reach final node (to set velocities). |
Definition at line 127 of file nodes_variables.cc.
|
overridevirtual |
Sets some node positions and velocity from the optimization variables.
x | The 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.
Implements ifopt::Component.
Definition at line 65 of file nodes_variables.cc.
|
private |
Notifies the subscribed observers that the node values changes.
Definition at line 75 of file nodes_variables.cc.
|
protected |
the bounds on the node values.
Definition at line 214 of file nodes_variables.h.
|
protected |
Definition at line 216 of file nodes_variables.h.
|
protected |
Definition at line 215 of file nodes_variables.h.
|
static |
Definition at line 115 of file nodes_variables.h.
|
private |
Definition at line 223 of file nodes_variables.h.