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/variables/phase_durations.h>
00031
00032 #include <numeric>
00033
00034 #include <towr/variables/variable_names.h>
00035 #include <towr/variables/spline.h>
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
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
00125 if (!in_last_phase)
00126 jac.col(current_phase) = dx_dT;
00127
00128 for (int phase=0; phase<current_phase; ++phase) {
00129
00130 jac.col(phase) = -1*xd;
00131
00132
00133
00134 if (in_last_phase)
00135 jac.col(phase) -= dx_dT;
00136 }
00137
00138
00139
00140
00141 return jac.sparseView(1.0, -1.0);
00142 }
00143
00144 }
00145
00146