35 std::vector<PhaseNodes::PolyInfo>
40 std::vector<PolyInfo> polynomial_info;
46 bool phase_constant = first_phase_constant;
48 for (
int i=0; i<phase_count; ++i) {
50 polynomial_info.push_back(PolyInfo(i,0,1,
true));
52 for (
int j=0; j<n_polys_in_changing_phase; ++j)
53 polynomial_info.push_back(PolyInfo(i,j,n_polys_in_changing_phase,
false));
55 phase_constant = !phase_constant;
58 return polynomial_info;
62 bool is_in_contact_at_start,
63 const std::string& name,
64 int n_polys_in_changing_phase,
77 else if (type ==
Force)
90 poly_durations.push_back(phase_durations.at(info.phase_)/info.n_polys_in_phase_);
93 return poly_durations;
100 return 1./n_polys_in_phase;
109 std::map<PhaseNodes::OptNodeIs, PhaseNodes::NodeIds>
112 std::map<OptNodeIs, NodeIds> optnode_to_node;
115 for (
int i=0; i<polynomial_info.size(); ++i) {
116 int node_id_start =
GetNodeId(i, Side::Start);
118 optnode_to_node[opt_id].push_back(node_id_start);
120 if (!polynomial_info.at(i).is_constant_)
124 int last_node_id = polynomial_info.size();
125 optnode_to_node[opt_id].push_back(last_node_id);
127 return optnode_to_node;
130 std::vector<PhaseNodes::IndexInfo>
133 std::vector<IndexInfo> nodes;
136 int n_opt_values_per_node_ = 2*
GetDim();
137 int internal_id = idx%n_opt_values_per_node_;
145 int opt_node = std::floor(idx/n_opt_values_per_node_);
148 nodes.push_back(node);
157 bool is_constant =
false;
179 for (
int id=0;
id<
GetNodes().size(); ++id)
181 node_ids.push_back(
id);
221 std::vector<int> poly_ids;
222 int last_node_id =
GetNodes().size()-1;
225 poly_ids.push_back(0);
226 else if (node_id==last_node_id)
227 poly_ids.push_back(last_node_id-1);
229 poly_ids.push_back(node_id-1);
230 poly_ids.push_back(node_id);
239 for (
int i=0; i<GetRows(); ++i) {
247 if (idx.node_deriv_ ==
kVel)
248 bounds_.at(i) = ifopt::BoundZero;
254 if (idx.node_deriv_ ==
kVel && idx.node_dim_ ==
Z)
255 bounds_.at(i) = ifopt::BoundZero;
269 for (
int i=0; i<GetRows(); ++i) {
285 bounds_.at(i) = ifopt::BoundZero;
292 int num_polys_in_phase,
bool is_constant)
294 poly_in_phase_(poly_id_in_phase),
295 n_polys_in_phase_(num_polys_in_phase),
296 is_constant_(is_constant)
virtual bool IsInConstantPhase(int polynomial_id) const
Is the polynomial constant, so not changing the value.
virtual VecDurations ConvertPhaseToPolyDurations(const VecDurations &phase_durations) const
Converts durations of swing and stance phases to polynomial durations.
void SetBoundsEEMotion()
Sets the bounds on the node variables to model foot motions.
NodeIds GetIndicesOfNonConstantNodes() const
The indices of those nodes that don't belong to a constant phase.
static std::map< OptNodeIs, NodeIds > GetOptNodeToNodeMappings(const std::vector< PolyInfo > &)
std::map< OptNodeIs, NodeIds > optnode_to_node_
void SetBoundsEEForce()
Sets the bounds on the node variables to model foot forces.
virtual double GetDerivativeOfPolyDurationWrtPhaseDuration(int polynomial_id) const
How a change in the phase duration affects the polynomial duration.
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.
std::vector< double > VecDurations
Holds semantic information each polynomial in spline.
std::vector< PolyInfo > polynomial_info_
std::vector< PhaseNodes::PolyInfo > BuildPolyInfos(int phase_count, bool is_in_contact_at_start, int n_polys_in_changing_phase, PhaseNodes::Type type)
std::vector< int > NodeIds
int node_dim_
the dimension (x,y,z) of that optimization index.
PhaseNodes(int phase_count, bool in_contact_start, const std::string &var_name, int n_polys_in_changing_phase, Type type)
Constructs a variable set of node variables.
Position and velocity of nodes used to generate a Hermite spline.
PolyInfo(int phase, int poly_in_phase, int n_polys_in_phase, bool is_const)
std::vector< int > GetAdjacentPolyIds(int node_id) const
int GetPolyIDAtStartOfPhase(int phase) const
void InitMembers(int n_nodes, int n_variables)
initializes the member variables.
VecBound bounds_
the bounds on the node values.
static int GetNodeId(int poly_id, Side side)
The node ID that belongs to a specific side of a specific polynomial.
int GetPolynomialCount() const
Dx node_deriv_
The derivative (pos,vel) of that optimziation index.
Holds information about the node the optimization index represents.
int GetPhase(int node_id) const
int node_id_
The ID of the node of the optimization index.
int GetNodeIDAtStartOfPhase(int phase) const
virtual std::vector< IndexInfo > GetNodeInfoAtOptIndex(int idx) const override
The node information that the optimization index represents.
virtual int GetNumberOfPrevPolynomialsInPhase(int polynomial_id) const
How many polynomials in the current phase come before.
const std::vector< Node > GetNodes() const