30 #ifndef TOWR_CONSTRAINTS_BASE_MOTION_CONSTRAINT_H_ 31 #define TOWR_CONSTRAINTS_BASE_MOTION_CONSTRAINT_H_ 68 int GetRow (
int node,
int dim)
const;
VecBound node_bounds_
same bounds for each discretized node
virtual ~BaseMotionConstraint()=default
Constraints evaluated at discretized times along a trajectory.
std::shared_ptr< NodeSpline > Ptr
BaseMotionConstraint(double T, double dt, const SplineHolder &spline_holder)
Links the base variables and sets hardcoded bounds on the state.
void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian &) const override
Sets Jacobian rows at a specific time t, corresponding to node k.
Builds splines from node values (pos/vel) and durations.
NodeSpline::Ptr base_angular_
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
void UpdateConstraintAtInstance(double t, int k, VectorXd &g) const override
Sets the constraint value a specific time t, corresponding to node k.
void UpdateBoundsAtInstance(double t, int k, VecBound &) const override
Sets upper/lower bound a specific time t, corresponding to node k.
NodeSpline::Ptr base_linear_
std::vector< Bounds > VecBound
Keeps the 6D base motion in a specified range.
int GetRow(int node, int dim) const