Variables fully defining the endeffector forces. More...
#include <nodes_variables_phase_based.h>

Public Member Functions | |
| OptIndexMap | GetPhaseBasedEEParameterization () |
| NodesVariablesEEForce (int phase_count, bool is_in_contact_at_start, const std::string &name, int n_polys_in_changing_phase) | |
| virtual | ~NodesVariablesEEForce ()=default |
Public Member Functions inherited from towr::NodesVariablesPhaseBased | |
| virtual VecDurations | ConvertPhaseToPolyDurations (const VecDurations &phase_durations) const |
| Converts durations of swing and stance phases to polynomial durations. More... | |
| virtual double | GetDerivativeOfPolyDurationWrtPhaseDuration (int polynomial_id) const |
| How a change in the phase duration affects the polynomial duration. More... | |
| NodeIds | GetIndicesOfNonConstantNodes () const |
| The indices of those nodes that don't belong to a constant phase. More... | |
| int | GetNodeIDAtStartOfPhase (int phase) const |
| virtual int | GetNumberOfPrevPolynomialsInPhase (int polynomial_id) const |
| How many polynomials in the current phase come before. More... | |
| 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. More... | |
| virtual bool | IsInConstantPhase (int polynomial_id) const |
| Is the polynomial constant, so not changing the value. More... | |
| NodesVariablesPhaseBased (int phase_count, bool first_phase_constant, const std::string &var_name, int n_polys_in_changing_phase) | |
| Constructs a variable set of node variables. More... | |
| virtual | ~NodesVariablesPhaseBased ()=default |
Public Member Functions inherited from towr::NodesVariables | |
| 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 |
| 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 |
Additional Inherited Members | |
Public Types inherited from towr::NodesVariablesPhaseBased | |
| using | NodeIds = std::vector< int > |
| using | OptIndexMap = std::map< int, std::vector< NodeValueInfo > > |
| using | Ptr = std::shared_ptr< NodesVariablesPhaseBased > |
Public Types inherited from towr::NodesVariables | |
| 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 |
Static Public Member Functions inherited from towr::NodesVariables | |
| 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 inherited from towr::NodesVariables | |
| static const int | NodeValueNotOptimized = -1 |
Static Public Attributes inherited from ifopt::Component | |
| static const int | kSpecifyLater |
Protected Member Functions inherited from towr::NodesVariablesPhaseBased | |
| std::vector< NodeValueInfo > | GetNodeValuesInfo (int idx) const override |
| Node values affected by one specific optimization variable. More... | |
| void | SetNumberOfVariables (int n_variables) |
Protected Member Functions inherited from towr::NodesVariables | |
| NodesVariables (const std::string &variable_name) | |
| virtual | ~NodesVariables ()=default |
Protected Attributes inherited from towr::NodesVariablesPhaseBased | |
| OptIndexMap | index_to_node_value_info_ |
| Assign optimization variables to the correct node values. More... | |
Protected Attributes inherited from towr::NodesVariables | |
| VecBound | bounds_ |
| the bounds on the node values. More... | |
| int | n_dim_ |
| std::vector< Node > | nodes_ |
Variables fully defining the endeffector forces.
Definition at line 207 of file nodes_variables_phase_based.h.
| towr::NodesVariablesEEForce::NodesVariablesEEForce | ( | int | phase_count, |
| bool | is_in_contact_at_start, | ||
| const std::string & | name, | ||
| int | n_polys_in_changing_phase | ||
| ) |
Definition at line 255 of file nodes_variables_phase_based.cc.
|
virtualdefault |
| NodesVariablesEEForce::OptIndexMap towr::NodesVariablesEEForce::GetPhaseBasedEEParameterization | ( | ) |
Definition at line 269 of file nodes_variables_phase_based.cc.