56 return k6D*k + dimension;
87 jac_model =
model_->GetJacobianWrtBaseLin(jac_base_lin_pos,
96 for (
int ee=0; ee<
model_->GetEECount(); ++ee) {
99 jac_model =
model_->GetJacobianWrtForce(jac_ee_force, ee);
104 jac_model =
model_->GetJacobianWrtEEPos(jac_ee_pos, ee);
109 jac_model +=
model_->GetJacobianWrtForce(jac_f_dT, ee);
112 jac_model +=
model_->GetJacobianWrtEEPos(jac_x_dT, ee);
128 int n_ee =
model_->GetEECount();
129 std::vector<Eigen::Vector3d> ee_pos;
130 std::vector<Eigen::Vector3d> ee_force;
131 for (
int ee=0; ee<n_ee; ++ee) {
132 ee_force.push_back(
ee_forces_.at(ee)->GetPoint(t).p());
133 ee_pos.push_back(
ee_motion_.at(ee)->GetPoint(t).p());
136 model_->SetCurrent(com.p(), com.a(), w_R_b, omega, omega_dot, ee_force, ee_pos);
Constraints evaluated at discretized times along a trajectory.
static const Bounds BoundZero
DynamicConstraint(const DynamicModel::Ptr &model, double T, double dt, const SplineHolder &spline_holder)
Construct a Dynamic constraint.
void UpdateModel(double t) const
Updates the model with the current state and forces.
void UpdateConstraintAtInstance(double t, int k, VectorXd &g) const override
Sets the constraint value a specific time t, corresponding to node k.
EulerConverter base_angular_
angular base state
NodeSpline::Ptr base_linear_
lin. base pos/vel/acc in world frame
static std::string EESchedule(uint ee)
void UpdateJacobianAtInstance(double t, int k, std::string, Jacobian &) const override
Sets Jacobian rows at a specific time t, corresponding to node k.
static const Dim6D AllDim6D[]
Vector3d GetAngularAccelerationInWorld(double t) const
Converts Euler angles, rates and rate derivatives o angular accelerations.
Builds splines from node values (pos/vel) and durations.
int GetNumberOfNodes() const
Converts Euler angles and derivatives to angular quantities.
NodeSpline::Ptr base_linear_
std::shared_ptr< DynamicModel > Ptr
void SetRows(int num_rows)
static std::string EEMotionNodes(uint ee)
std::vector< NodeSpline::Ptr > ee_force_
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
NodeSpline::Ptr base_angular_
std::vector< NodeSpline::Ptr > ee_forces_
endeffector forces in world frame.
Vector3d GetAngularVelocityInWorld(double t) const
Converts Euler angles and Euler rates to angular velocities.
void UpdateBoundsAtInstance(double t, int k, VecBound &bounds) const override
Sets upper/lower bound a specific time t, corresponding to node k.
std::vector< NodeSpline::Ptr > ee_motion_
endeffector position in world frame.
MatrixSXd GetRotationMatrixBaseToWorld(double t) const
Converts the Euler angles at time t to a rotation matrix.
static std::string EEForceNodes(uint ee)
static const std::string base_ang_nodes
DynamicModel::Ptr model_
the dynamic model (e.g. Centroidal)
std::vector< Bounds > VecBound
std::vector< NodeSpline::Ptr > ee_motion_
static const std::string base_lin_nodes
int GetRow(int k, Dim6D dimension) const
The row in the overall constraint for this evaluation time.