Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <towr/constraints/dynamic_constraint.h>
00031
00032 #include <towr/variables/variable_names.h>
00033 #include <towr/variables/cartesian_dimensions.h>
00034
00035 namespace towr {
00036
00037 DynamicConstraint::DynamicConstraint (const DynamicModel::Ptr& m,
00038 const Parameters& params,
00039 const SplineHolder& spline_holder)
00040 :TimeDiscretizationConstraint(params.t_total_,
00041 params.dt_constraint_dynamic_,
00042 "DynamicConstraint")
00043 {
00044 model_ = m;
00045
00046
00047 base_linear_ = spline_holder.base_linear_;
00048 base_angular_ = EulerConverter(spline_holder.base_angular_);
00049 ee_forces_ = spline_holder.ee_force_;
00050 ee_motion_ = spline_holder.ee_motion_;
00051
00052 SetRows(GetNumberOfNodes()*k6D);
00053 }
00054
00055 int
00056 DynamicConstraint::GetRow (int k, Dim6D dimension) const
00057 {
00058 return k6D*k + dimension;
00059 }
00060
00061 void
00062 DynamicConstraint::UpdateConstraintAtInstance(double t, int k, VectorXd& g) const
00063 {
00064 UpdateModel(t);
00065 g.segment(GetRow(k,AX), k6D) = model_->GetDynamicViolation();
00066 }
00067
00068 void
00069 DynamicConstraint::UpdateBoundsAtInstance(double t, int k, VecBound& bounds) const
00070 {
00071 for (auto dim : AllDim6D)
00072 bounds.at(GetRow(k,dim)) = ifopt::BoundZero;
00073 }
00074
00075 void
00076 DynamicConstraint::UpdateJacobianAtInstance(double t, int k, std::string var_set,
00077 Jacobian& jac) const
00078 {
00079 UpdateModel(t);
00080
00081 int n = jac.cols();
00082 Jacobian jac_model(k6D,n);
00083
00084
00085 if (var_set == id::base_lin_nodes) {
00086 Jacobian jac_base_lin_pos = base_linear_->GetJacobianWrtNodes(t,kPos);
00087 Jacobian jac_base_lin_acc = base_linear_->GetJacobianWrtNodes(t,kAcc);
00088
00089 jac_model = model_->GetJacobianWrtBaseLin(jac_base_lin_pos,
00090 jac_base_lin_acc);
00091 }
00092
00093 if (var_set == id::base_ang_nodes) {
00094 jac_model = model_->GetJacobianWrtBaseAng(base_angular_, t);
00095 }
00096
00097
00098
00099 for (int ee=0; ee<model_->GetEECount(); ++ee) {
00100
00101 if (var_set == id::EEForceNodes(ee)) {
00102 Jacobian jac_ee_force = ee_forces_.at(ee)->GetJacobianWrtNodes(t,kPos);
00103 jac_model = model_->GetJacobianWrtForce(jac_ee_force, ee);
00104 }
00105
00106 if (var_set == id::EEMotionNodes(ee)) {
00107 Jacobian jac_ee_pos = ee_motion_.at(ee)->GetJacobianWrtNodes(t,kPos);
00108 jac_model = model_->GetJacobianWrtEEPos(jac_ee_pos, ee);
00109 }
00110
00111 if (var_set == id::EESchedule(ee)) {
00112 Jacobian jac_f_dT = ee_forces_.at(ee)->GetJacobianOfPosWrtDurations(t);
00113 jac_model += model_->GetJacobianWrtForce(jac_f_dT, ee);
00114
00115 Jacobian jac_x_dT = ee_motion_.at(ee)->GetJacobianOfPosWrtDurations(t);
00116 jac_model += model_->GetJacobianWrtEEPos(jac_x_dT, ee);
00117 }
00118 }
00119
00120 jac.middleRows(GetRow(k,AX), k6D) = jac_model;
00121 }
00122
00123 void
00124 DynamicConstraint::UpdateModel (double t) const
00125 {
00126 auto com = base_linear_->GetPoint(t);
00127
00128 Eigen::Matrix3d w_R_b = base_angular_.GetRotationMatrixBaseToWorld(t);
00129 Eigen::Vector3d omega = base_angular_.GetAngularVelocityInWorld(t);
00130 Eigen::Vector3d omega_dot = base_angular_.GetAngularAccelerationInWorld(t);
00131
00132 int n_ee = model_->GetEECount();
00133 std::vector<Eigen::Vector3d> ee_pos;
00134 std::vector<Eigen::Vector3d> ee_force;
00135 for (int ee=0; ee<n_ee; ++ee) {
00136 ee_force.push_back(ee_forces_.at(ee)->GetPoint(t).p());
00137 ee_pos.push_back(ee_motion_.at(ee)->GetPoint(t).p());
00138 }
00139
00140 model_->SetCurrent(com.p(), com.a(), w_R_b, omega, omega_dot, ee_force, ee_pos);
00141 }
00142
00143 }