Nodes that are associated to either swing or stance phases. More...
#include <nodes_variables_phase_based.h>
Classes | |
struct | PolyInfo |
Holds semantic information each polynomial in spline. More... | |
Public Member Functions | |
virtual VecDurations | ConvertPhaseToPolyDurations (const VecDurations &phase_durations) const |
Converts durations of swing and stance phases to polynomial durations. | |
virtual double | GetDerivativeOfPolyDurationWrtPhaseDuration (int polynomial_id) const |
How a change in the phase duration affects the polynomial duration. | |
NodeIds | GetIndicesOfNonConstantNodes () const |
The indices of those nodes that don't belong to a constant phase. | |
int | GetNodeIDAtStartOfPhase (int phase) const |
virtual int | GetNumberOfPrevPolynomialsInPhase (int polynomial_id) const |
How many polynomials in the current phase come before. | |
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. | |
virtual bool | IsInConstantPhase (int polynomial_id) const |
Is the polynomial constant, so not changing the value. | |
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. | |
virtual | ~NodesVariablesPhaseBased () |
Protected Member Functions | |
std::vector< NodeValueInfo > | GetNodeValuesInfo (int idx) const override |
Node values affected by one specific optimization variable. | |
void | SetNumberOfVariables (int n_variables) |
Protected Attributes | |
OptIndexMap | index_to_node_value_info_ |
Assign optimization variables to the correct node values. | |
Private Member Functions | |
std::vector< int > | GetAdjacentPolyIds (int node_id) const |
IDs of the polynomial to the left and right of node_id. | |
int | GetPolyIDAtStartOfPhase (int phase) const |
ID of the first polynomial of a phase. | |
Private Attributes | |
std::vector< PolyInfo > | polynomial_info_ |
semantic information associated with each polynomial |
Nodes that are associated to either swing or stance phases.
**Not all node values must be optimized over**. We can for example fix node derivatives to 0.0 and also use the same optimization variable to fill to node positions. If the spline represents the position of an end-effector, this means that no matter which values the the solver chooses, the foot will never move during the stance phase. This is done in NodesVariablesEEMotion. A force spline is parameterized in the reverse way, with multiple nodes during stance phase. This is implemented in NodesVariablesEEForce.
#### Motion (dim: x) and force (dim: z) spline for one foot
A high-level explanation of this concept can be found here: https://youtu.be/KhWuLvb934g?t=1004
Definition at line 59 of file nodes_variables_phase_based.h.
towr::NodesVariablesPhaseBased::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.
phase_count | The number of phases (swing, stance) to represent. |
first_phase_constant | Whether first node belongs to a constant phase. |
var_name | The name given to this set of optimization variables. |
n_polys_in_changing_phase | How many polynomials should be used to paramerize each non-constant phase. |
Definition at line 60 of file nodes_variables_phase_based.cc.
virtual towr::NodesVariablesPhaseBased::~NodesVariablesPhaseBased | ( | ) | [virtual] |
NodesVariablesPhaseBased::VecDurations towr::NodesVariablesPhaseBased::ConvertPhaseToPolyDurations | ( | const VecDurations & | phase_durations | ) | const [virtual] |
Converts durations of swing and stance phases to polynomial durations.
phase_durations | The durations of alternating swing and stance phases. |
Definition at line 74 of file nodes_variables_phase_based.cc.
std::vector< int > towr::NodesVariablesPhaseBased::GetAdjacentPolyIds | ( | int | node_id | ) | const [private] |
IDs of the polynomial to the left and right of node_id.
Definition at line 164 of file nodes_variables_phase_based.cc.
double towr::NodesVariablesPhaseBased::GetDerivativeOfPolyDurationWrtPhaseDuration | ( | int | polynomial_id | ) | const [virtual] |
How a change in the phase duration affects the polynomial duration.
polynomial_id | The ID of the polynomial within the spline. |
If a phase is represented by multiple (3) equally timed polynomials, then T_poly = 1/3 * T_phase. The derivative of T_poly is then 1/3.
Definition at line 87 of file nodes_variables_phase_based.cc.
NodesVariablesPhaseBased::NodeIds towr::NodesVariablesPhaseBased::GetIndicesOfNonConstantNodes | ( | ) | const |
The indices of those nodes that don't belong to a constant phase.
For forces nodes these are the stance phases (can produce force), and for feet these are the swing phases (can move end-effector).
Definition at line 120 of file nodes_variables_phase_based.cc.
int towr::NodesVariablesPhaseBased::GetNodeIDAtStartOfPhase | ( | int | phase | ) | const |
Definition at line 157 of file nodes_variables_phase_based.cc.
std::vector<NodeValueInfo> towr::NodesVariablesPhaseBased::GetNodeValuesInfo | ( | int | opt_idx | ) | const [inline, override, protected, 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().
Implements towr::NodesVariables.
Definition at line 168 of file nodes_variables_phase_based.h.
int towr::NodesVariablesPhaseBased::GetNumberOfPrevPolynomialsInPhase | ( | int | polynomial_id | ) | const [virtual] |
How many polynomials in the current phase come before.
polynomial_id | The ID of the polynomial within the spline. |
If a phase is represented by multiple (3) polynomials, and the current polynomial corresponds to the third one in the phase, then 2 polynomials come before it.
Definition at line 94 of file nodes_variables_phase_based.cc.
int towr::NodesVariablesPhaseBased::GetPhase | ( | int | node_id | ) | const |
Only makes sense if left and right polynomial belong to same phase.
Definition at line 132 of file nodes_variables_phase_based.cc.
int towr::NodesVariablesPhaseBased::GetPolyIDAtStartOfPhase | ( | int | phase | ) | const [private] |
ID of the first polynomial of a phase.
Definition at line 141 of file nodes_variables_phase_based.cc.
Eigen::Vector3d towr::NodesVariablesPhaseBased::GetValueAtStartOfPhase | ( | int | phase | ) | const |
Definition at line 150 of file nodes_variables_phase_based.cc.
bool towr::NodesVariablesPhaseBased::IsConstantNode | ( | int | node_id | ) | const [virtual] |
node is constant if either left or right polynomial belongs to a constant phase.
Definition at line 100 of file nodes_variables_phase_based.cc.
bool towr::NodesVariablesPhaseBased::IsInConstantPhase | ( | int | polynomial_id | ) | const [virtual] |
Is the polynomial constant, so not changing the value.
polynomial_id | The ID of the polynomial within the spline. |
Definition at line 114 of file nodes_variables_phase_based.cc.
void towr::NodesVariablesPhaseBased::SetNumberOfVariables | ( | int | n_variables | ) | [protected] |
Definition at line 191 of file nodes_variables_phase_based.cc.
OptIndexMap towr::NodesVariablesPhaseBased::index_to_node_value_info_ [protected] |
Assign optimization variables to the correct node values.
This map is the main element that implements _Phase-based End-effector Parameterization_ and is generated by the derived Motion and Force classes.
Definition at line 167 of file nodes_variables_phase_based.h.
std::vector<PolyInfo> towr::NodesVariablesPhaseBased::polynomial_info_ [private] |
semantic information associated with each polynomial
Definition at line 176 of file nodes_variables_phase_based.h.