dynamic_constraint.cc
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without
00005 modification, are permitted provided that the following conditions are met:
00006 
00007 * Redistributions of source code must retain the above copyright notice, this
00008   list of conditions and the following disclaimer.
00009 
00010 * Redistributions in binary form must reproduce the above copyright notice,
00011   this list of conditions and the following disclaimer in the documentation
00012   and/or other materials provided with the distribution.
00013 
00014 * Neither the name of the copyright holder nor the names of its
00015   contributors may be used to endorse or promote products derived from
00016   this software without specific prior written permission.
00017 
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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   // link with up-to-date spline variables
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   // sensitivity of dynamic constraint w.r.t base variables.
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   // sensitivity of dynamic constraint w.r.t. endeffector variables
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 } /* namespace towr */


towr_core
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 9 2018 03:12:44