range_of_motion_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/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 } /* namespace xpp */
00112 


towr
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 15 2019 02:42:32