phase_durations.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/variables/phase_durations.h>
00031 
00032 #include <numeric> // std::accumulate
00033 
00034 #include <towr/variables/variable_names.h>
00035 #include <towr/variables/spline.h> // for Spline::GetSegmentID()
00036 
00037 
00038 namespace towr {
00039 
00040 
00041 PhaseDurations::PhaseDurations (EndeffectorID ee,
00042                                 const VecDurations& timings,
00043                                 bool is_first_phase_in_contact,
00044                                 double min_duration,
00045                                 double max_duration)
00046     // -1 since last phase-duration is not optimized over, but comes from total time
00047     :VariableSet(timings.size()-1, id::EESchedule(ee))
00048 {
00049   durations_ = timings;
00050   t_total_ = std::accumulate(timings.begin(), timings.end(), 0.0);
00051   phase_duration_bounds_ = ifopt::Bounds(min_duration, max_duration);
00052   initial_contact_state_ = is_first_phase_in_contact;
00053 }
00054 
00055 void
00056 PhaseDurations::AddObserver (PhaseDurationsObserver* const o)
00057 {
00058   observers_.push_back(o);
00059 }
00060 
00061 void
00062 PhaseDurations::UpdateObservers () const
00063 {
00064   for (auto& spline : observers_)
00065     spline->UpdatePolynomialDurations();
00066 }
00067 
00068 Eigen::VectorXd
00069 PhaseDurations::GetValues () const
00070 {
00071   VectorXd x(GetRows());
00072 
00073   for (int i=0; i<x.rows(); ++i)
00074     x(i) = durations_.at(i);
00075 
00076   return x;
00077 }
00078 
00079 void
00080 PhaseDurations::SetVariables (const VectorXd& x)
00081 {
00082   for (int i=0; i<GetRows(); ++i)
00083     durations_.at(i) = x(i);
00084 
00085   durations_.back() =  t_total_ - x.sum();
00086   assert(durations_.back()>0);
00087   UpdateObservers();
00088 }
00089 
00090 PhaseDurations::VecBound
00091 PhaseDurations::GetBounds () const
00092 {
00093   VecBound bounds;
00094 
00095   for (int i=0; i<GetRows(); ++i)
00096     bounds.push_back(phase_duration_bounds_);
00097 
00098   return bounds;
00099 }
00100 
00101 PhaseDurations::VecDurations
00102 PhaseDurations::GetPhaseDurations() const
00103 {
00104   return durations_;
00105 }
00106 
00107 bool
00108 PhaseDurations::IsContactPhase (double t) const
00109 {
00110   int phase_id = Spline::GetSegmentID(t, durations_);
00111   return phase_id%2 == 0? initial_contact_state_ : !initial_contact_state_;
00112 }
00113 
00114 PhaseDurations::Jacobian
00115 PhaseDurations::GetJacobianOfPos (int current_phase,
00116                                   const VectorXd& dx_dT,
00117                                   const VectorXd& xd) const
00118 {
00119   int n_dim = xd.rows();
00120   Eigen::MatrixXd jac = Eigen::MatrixXd::Zero(n_dim, GetRows());
00121 
00122   bool in_last_phase = (current_phase == durations_.size()-1);
00123 
00124   // duration of current phase expands and compressed spline
00125   if (!in_last_phase)
00126     jac.col(current_phase) = dx_dT;
00127 
00128   for (int phase=0; phase<current_phase; ++phase) {
00129     // each previous durations shifts spline along time axis
00130     jac.col(phase) = -1*xd;
00131 
00132     // in last phase previous duration cause expansion/compression of spline
00133     // as final time is fixed.
00134     if (in_last_phase)
00135       jac.col(phase) -= dx_dT;
00136   }
00137 
00138   // convert to sparse, but also regard 0.0 as non-zero element, because
00139   // could turn nonzero during the course of the program
00140   // as durations change and t_global falls into different spline
00141   return jac.sparseView(1.0, -1.0);
00142 }
00143 
00144 } /* namespace towr */
00145 
00146 


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