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/range_of_motion_constraint.h>
00031 #include <towr/variables/variable_names.h>
00032
00033 namespace towr {
00034
00035 RangeOfMotionConstraint::RangeOfMotionConstraint (const KinematicModel::Ptr& model,
00036 double T, double dt,
00037 const EE& ee,
00038 const SplineHolder& spline_holder)
00039 :TimeDiscretizationConstraint(T, dt, "rangeofmotion-" + std::to_string(ee))
00040 {
00041 base_linear_ = spline_holder.base_linear_;
00042 base_angular_ = EulerConverter(spline_holder.base_angular_);
00043 ee_motion_ = spline_holder.ee_motion_.at(ee);
00044
00045 max_deviation_from_nominal_ = model->GetMaximumDeviationFromNominal();
00046 nominal_ee_pos_B_ = model->GetNominalStanceInBase().at(ee);
00047 ee_ = ee;
00048
00049 SetRows(GetNumberOfNodes()*k3D);
00050 }
00051
00052 int
00053 RangeOfMotionConstraint::GetRow (int node, int dim) const
00054 {
00055 return node*k3D + dim;
00056 }
00057
00058 void
00059 RangeOfMotionConstraint::UpdateConstraintAtInstance (double t, int k, VectorXd& g) const
00060 {
00061 Vector3d base_W = base_linear_->GetPoint(t).p();
00062 Vector3d pos_ee_W = ee_motion_->GetPoint(t).p();
00063 EulerConverter::MatrixSXd b_R_w = base_angular_.GetRotationMatrixBaseToWorld(t).transpose();
00064
00065 Vector3d vector_base_to_ee_W = pos_ee_W - base_W;
00066 Vector3d vector_base_to_ee_B = b_R_w*(vector_base_to_ee_W);
00067
00068 g.middleRows(GetRow(k, X), k3D) = vector_base_to_ee_B;
00069 }
00070
00071 void
00072 RangeOfMotionConstraint::UpdateBoundsAtInstance (double t, int k, VecBound& bounds) const
00073 {
00074 for (int dim=0; dim<k3D; ++dim) {
00075 ifopt::Bounds b;
00076 b += nominal_ee_pos_B_(dim);
00077 b.upper_ += max_deviation_from_nominal_(dim);
00078 b.lower_ -= max_deviation_from_nominal_(dim);
00079 bounds.at(GetRow(k,dim)) = b;
00080 }
00081 }
00082
00083 void
00084 RangeOfMotionConstraint::UpdateJacobianAtInstance (double t, int k,
00085 std::string var_set,
00086 Jacobian& jac) const
00087 {
00088 EulerConverter::MatrixSXd b_R_w = base_angular_.GetRotationMatrixBaseToWorld(t).transpose();
00089 int row_start = GetRow(k,X);
00090
00091 if (var_set == id::base_lin_nodes) {
00092 jac.middleRows(row_start, k3D) = -1*b_R_w*base_linear_->GetJacobianWrtNodes(t, kPos);
00093 }
00094
00095 if (var_set == id::base_ang_nodes) {
00096 Vector3d base_W = base_linear_->GetPoint(t).p();
00097 Vector3d ee_pos_W = ee_motion_->GetPoint(t).p();
00098 Vector3d r_W = ee_pos_W - base_W;
00099 jac.middleRows(row_start, k3D) = base_angular_.DerivOfRotVecMult(t,r_W, true);
00100 }
00101
00102 if (var_set == id::EEMotionNodes(ee_)) {
00103 jac.middleRows(row_start, k3D) = b_R_w*ee_motion_->GetJacobianWrtNodes(t,kPos);
00104 }
00105
00106 if (var_set == id::EESchedule(ee_)) {
00107 jac.middleRows(row_start, k3D) = b_R_w*ee_motion_->GetJacobianOfPosWrtDurations(t);
00108 }
00109 }
00110
00111 }
00112