37 const VecTimes& polynomial_durations)
38 :
Spline(polynomial_durations, node_variables->GetDim()),
50 cubic_polys_.at(i).SetNodes(nodes.front(), nodes.back());
65 int id;
double t_local;
86 Jacobian& jac,
bool fill_with_zeros)
const 88 for (
int idx=0; idx<jac.cols(); ++idx) {
90 for (
auto side : {NodesVariables::Side::Start, NodesVariables::Side::End}) {
93 if (node == nvi.id_) {
96 if (side == NodesVariables::Side::Start)
97 val =
cubic_polys_.at(poly_id).GetDerivativeWrtStartNode(dxdt, nvi.deriv_, t_local);
98 else if (side == NodesVariables::Side::End)
99 val =
cubic_polys_.at(poly_id).GetDerivativeWrtEndNode(dxdt, nvi.deriv_, t_local);
107 jac.coeffRef(nvi.dim_, idx) += val;
Base class to receive up-to-date values of the NodeVariables.
std::pair< int, double > GetLocalTime(double t_global, const VecTimes &d) const
How much time of the current segment has passed at t_global.
Jacobian GetJacobianWrtNodes(double t, Dx dxdt) const
How the spline changes when the node values change.
Jacobian jac_wrt_nodes_structure_
A spline built from a sequence of cubic polynomials.
NodeSubjectPtr node_values_
std::vector< double > VecTimes
void UpdateNodes()
Called by subject to update the polynomials with new node values.
VecPoly cubic_polys_
the sequence of polynomials making up the spline.
Position and velocity of nodes used to generate a Hermite spline.
static int GetNodeId(int poly_id, Side side)
The node ID that belongs to a specific side of a specific polynomial.
void UpdatePolynomialCoeff()
Updates the cubic-Hermite polynomial coefficients using the currently set nodes values and durations...
VecTimes GetPolyDurations() const
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
NodeSpline(NodeSubjectPtr const node_variables, const VecTimes &polynomial_durations)
Constructs a spline with constant durations.
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 FillJacobianWrtNodes(int poly_id, double t_local, Dx dxdt, Jacobian &jac, bool fill_with_zeros) const
Fills specific elements of the Jacobian with respect to nodes.
int GetNodeVariablesCount() const
Dx
< the values or derivative. For motions e.g. position, velocity, ...