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   // the sum of all phase durations should never be larger than the total time of
00083   // the trajectory. This would e.g. query constraints after duration of the trajectory and
00084   // causes undefined behavior. However, when IPOPT optimizes the phase durations,
00085   // it's not possible to enforce that in every iteration this condition is fulfilled. Sure,
00086   // we can set this as a constraint, but during the solution process constraints might still
00087   // be violated.
00088   // Fortunately, violation of this doesn't seem to mess up IPOPT too much and a solution is
00089   // often found. So if you get this error you can ignore it by compiling in Release mode,
00090   // but I'm leaving this in here to show that this is undefined behavior and a clean
00091   // implementation is still required. PR desired ;)
00092   assert(t_total_>x.sum());
00093 
00094   for (int i=0; i<GetRows(); ++i)
00095     durations_.at(i) = x(i);
00096 
00097   // last phase duration not optimized, used to fill up to total time.
00098   durations_.back() =  t_total_ - x.sum();
00099   UpdateObservers();
00100 }
00101 
00102 PhaseDurations::VecBound
00103 PhaseDurations::GetBounds () const
00104 {
00105   VecBound bounds;
00106 
00107   for (int i=0; i<GetRows(); ++i)
00108     bounds.push_back(phase_duration_bounds_);
00109 
00110   return bounds;
00111 }
00112 
00113 PhaseDurations::VecDurations
00114 PhaseDurations::GetPhaseDurations() const
00115 {
00116   return durations_;
00117 }
00118 
00119 bool
00120 PhaseDurations::IsContactPhase (double t) const
00121 {
00122   int phase_id = Spline::GetSegmentID(t, durations_);
00123   return phase_id%2 == 0? initial_contact_state_ : !initial_contact_state_;
00124 }
00125 
00126 PhaseDurations::Jacobian
00127 PhaseDurations::GetJacobianOfPos (int current_phase,
00128                                   const VectorXd& dx_dT,
00129                                   const VectorXd& xd) const
00130 {
00131   int n_dim = xd.rows();
00132   Eigen::MatrixXd jac = Eigen::MatrixXd::Zero(n_dim, GetRows());
00133 
00134   bool in_last_phase = (current_phase == durations_.size()-1);
00135 
00136   // duration of current phase expands and compressed spline
00137   if (!in_last_phase)
00138     jac.col(current_phase) = dx_dT;
00139 
00140   for (int phase=0; phase<current_phase; ++phase) {
00141     // each previous durations shifts spline along time axis
00142     jac.col(phase) = -1*xd;
00143 
00144     // in last phase previous duration cause expansion/compression of spline
00145     // as final time is fixed.
00146     if (in_last_phase)
00147       jac.col(phase) -= dx_dT;
00148   }
00149 
00150   // convert to sparse, but also regard 0.0 as non-zero element, because
00151   // could turn nonzero during the course of the program
00152   // as durations change and t_global falls into different spline
00153   return jac.sparseView(1.0, -1.0);
00154 }
00155 
00156 } /* namespace towr */
00157 
00158 


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