30 #ifndef TOWR_TOWR_SRC_NODE_SPLINE_H_ 31 #define TOWR_TOWR_SRC_NODE_SPLINE_H_ 34 #include <Eigen/Sparse> 51 using Ptr = std::shared_ptr<NodeSpline>;
52 using Jacobian = Eigen::SparseMatrix<double, Eigen::RowMajor>;
60 const VecTimes& polynomial_durations);
119 Jacobian& jac,
bool fill_with_zeros)
const;
Base class to receive up-to-date values of the NodeVariables.
Jacobian GetJacobianWrtNodes(double t, Dx dxdt) const
How the spline changes when the node values change.
std::shared_ptr< NodeSpline > Ptr
A spline built from node values and fixed polynomial durations.
Jacobian jac_wrt_nodes_structure_
A spline built from a sequence of cubic polynomials.
std::vector< double > VecTimes
void UpdateNodes()
Called by subject to update the polynomials with new node values.
Position and velocity of nodes used to generate a Hermite spline.
virtual Jacobian GetJacobianOfPosWrtDurations(double t) const
How the spline position changes when the polynomial durations change.
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
NodeSpline(NodeSubjectPtr const node_variables, const VecTimes &polynomial_durations)
Constructs a spline with constant durations.
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, ...