30 #ifndef TOWR_CONSTRAINTS_RANGE_OF_MOTION_CONSTRAINT_H_ 31 #define TOWR_CONSTRAINTS_RANGE_OF_MOTION_CONSTRAINT_H_ 88 int GetRow(
int node,
int dimension)
const;
Constraints evaluated at discretized times along a trajectory.
NodeSpline::Ptr ee_motion_
the linear position of the endeffectors.
std::shared_ptr< NodeSpline > Ptr
std::shared_ptr< KinematicModel > Ptr
int GetRow(int node, int dimension) const
Builds splines from node values (pos/vel) and durations.
Eigen::Vector3d nominal_ee_pos_B_
Converts Euler angles and derivatives to angular quantities.
Eigen::Vector3d max_deviation_from_nominal_
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
EulerConverter base_angular_
the orientation of the base.
Constrains an endeffector to lie in a box around the nominal stance.
RangeOfMotionConstraint(const KinematicModel::Ptr &robot_model, double T, double dt, const EE &ee, const SplineHolder &spline_holder)
Constructs a constraint instance.
virtual ~RangeOfMotionConstraint()=default
void UpdateConstraintAtInstance(double t, int k, VectorXd &g) const override
Sets the constraint value a specific time t, corresponding to node k.
NodeSpline::Ptr base_linear_
the linear position of the base.
void UpdateBoundsAtInstance(double t, int k, VecBound &) const override
Sets upper/lower bound a specific time t, corresponding to node k.
std::vector< Bounds > VecBound
void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian &) const override
Sets Jacobian rows at a specific time t, corresponding to node k.