36 : VariableSet(kSpecifyLater, name)
44 for (
int idx=0; idx<
GetRows(); ++idx)
57 for (
int idx=0; idx<x.rows(); ++idx)
59 x(idx) =
nodes_.at(nvi.id_).at(nvi.deriv_)(nvi.dim_);
67 for (
int idx=0; idx<x.rows(); ++idx)
69 nodes_.at(nvi.id_).at(nvi.deriv_)(nvi.dim_) = x(idx);
90 return poly_id + side;
93 const std::vector<Node>
96 std::vector<Node> nodes;
120 const std::vector<Node>
133 VectorXd dp = final_val-initial_val;
134 VectorXd average_velocity = dp / t_total;
135 int num_nodes =
nodes_.size();
137 for (
int idx=0; idx<
GetRows(); ++idx) {
140 if (nvi.deriv_ ==
kPos) {
141 VectorXd pos = initial_val + nvi.id_/
static_cast<double>(num_nodes-1)*dp;
142 nodes_.at(nvi.id_).at(
kPos)(nvi.dim_) = pos(nvi.dim_);
145 if (nvi.deriv_ ==
kVel) {
146 nodes_.at(nvi.id_).at(
kVel)(nvi.dim_) = average_velocity(nvi.dim_);
154 const std::vector<int>& dimensions,
157 for (
auto dim : dimensions)
164 for (
int idx=0; idx<
GetRows(); ++idx)
193 return (id_ == right.
id_)
194 && (deriv_ == right.
deriv_)
195 && (dim_ == right.
dim_);
Base class to receive up-to-date values of the NodeVariables.
const std::vector< Node > GetNodes() const
VectorXd GetValues() const override
Pure optimization variables that define the nodes.
int id_
ID of the associated node (0 =< id < number of nodes in spline).
void AddBound(const NodeValueInfo &node_info, double value)
Restricts a specific optimization variables.
NodesVariables(const std::string &variable_name)
void SetVariables(const VectorXd &x) override
Sets some node positions and velocity from the optimization variables.
int dim_
Dimension (x,y,z) of that derivative.
static const int NodeValueNotOptimized
std::vector< Node > nodes_
static int GetNodeId(int poly_id, Side side)
The node ID that belongs to a specific side of a specific polynomial.
Semantic information associated with a scalar node value.
VecBound GetBounds() const override
int GetPolynomialCount() const
Dx deriv_
Derivative (pos,vel) of the node with that ID.
void UpdateObservers() const
Notifies the subscribed observers that the node values changes.
void AddStartBound(Dx deriv, const std::vector< int > &dimensions, const VectorXd &val)
Restricts the first node in the spline.
virtual std::vector< NodeValueInfo > GetNodeValuesInfo(int opt_idx) const =0
Node values affected by one specific optimization variable.
const std::vector< Node > GetBoundaryNodes(int poly_id) const
void AddBounds(int node_id, Dx deriv, const std::vector< int > &dim, const VectorXd &values)
Bounds a specific node variables.
int GetOptIndex(const NodeValueInfo &nvi) const
Index in the optimization vector for a specific nodes' pos/vel.
void AddFinalBound(Dx deriv, const std::vector< int > &dimensions, const VectorXd &val)
Restricts the last node in the spline.
void SetByLinearInterpolation(const VectorXd &initial_val, const VectorXd &final_val, double t_total)
Sets nodes pos/vel equally spaced from initial to final position.
VecBound bounds_
the bounds on the node values.
std::vector< Bounds > VecBound
void AddObserver(ObserverPtr const spline)
Adds a dependent observer that gets notified when the nodes change.
std::vector< ObserverPtr > observers_
Dx
< the values or derivative. For motions e.g. position, velocity, ...
int operator==(const NodeValueInfo &right) const