taylor_model.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00037 #include "fcl/ccd/taylor_model.h"
00038 #include <cassert>
00039 #include <iostream>
00040 #include <cmath>
00041 #include <boost/math/constants/constants.hpp>
00042 
00043 
00044 namespace fcl
00045 {
00046 
00047 TaylorModel::TaylorModel()
00048 {
00049   coeffs_[0] = coeffs_[1] = coeffs_[2] = coeffs_[3] = 0;
00050 }
00051 
00052 TaylorModel::TaylorModel(const boost::shared_ptr<TimeInterval>& time_interval) : time_interval_(time_interval)
00053 {
00054   coeffs_[0] = coeffs_[1] = coeffs_[2] = coeffs_[3] = 0;
00055 }
00056 
00057 TaylorModel::TaylorModel(FCL_REAL coeff, const boost::shared_ptr<TimeInterval>& time_interval) : time_interval_(time_interval)
00058 {
00059   coeffs_[0] = coeff;
00060   coeffs_[1] = coeffs_[2] = coeffs_[3] = r_[0] = r_[1] = 0;
00061 }
00062 
00063 TaylorModel::TaylorModel(FCL_REAL coeffs[3], const Interval& r, const boost::shared_ptr<TimeInterval>& time_interval) : time_interval_(time_interval)
00064 {
00065   coeffs_[0] = coeffs[0];
00066   coeffs_[1] = coeffs[1];
00067   coeffs_[2] = coeffs[2];
00068   coeffs_[3] = coeffs[3];
00069 
00070   r_ = r;
00071 }
00072 
00073 TaylorModel::TaylorModel(FCL_REAL c0, FCL_REAL c1, FCL_REAL c2, FCL_REAL c3, const Interval& r, const boost::shared_ptr<TimeInterval>& time_interval) : time_interval_(time_interval)
00074 {
00075   coeffs_[0] = c0;
00076   coeffs_[1] = c1;
00077   coeffs_[2] = c2;
00078   coeffs_[3] = c3;
00079 
00080   r_ = r;
00081 }
00082 
00083 void TaylorModel::setTimeInterval(FCL_REAL l, FCL_REAL r)
00084 {
00085   time_interval_->t_.setValue(l, r);
00086   time_interval_->t2_.setValue(l * time_interval_->t_[0], r * time_interval_->t_[1]);
00087   time_interval_->t3_.setValue(l * time_interval_->t2_[0], r * time_interval_->t2_[1]);
00088   time_interval_->t4_.setValue(l * time_interval_->t3_[0], r * time_interval_->t3_[1]);
00089   time_interval_->t5_.setValue(l * time_interval_->t4_[0], r * time_interval_->t4_[1]);
00090   time_interval_->t6_.setValue(l * time_interval_->t5_[0], r * time_interval_->t5_[1]);
00091 }
00092 
00093 TaylorModel TaylorModel::operator + (FCL_REAL d) const
00094 {
00095   return TaylorModel(coeffs_[0] + d, coeffs_[1], coeffs_[2], coeffs_[3], r_, time_interval_);
00096 }
00097 
00098 TaylorModel& TaylorModel::operator += (FCL_REAL d)
00099 {
00100   coeffs_[0] += d;
00101   return *this;
00102 }
00103 
00104 TaylorModel TaylorModel::operator + (const TaylorModel& other) const
00105 {
00106   assert(other.time_interval_ == time_interval_);
00107   return TaylorModel(coeffs_[0] + other.coeffs_[0], coeffs_[1] + other.coeffs_[1], coeffs_[2] + other.coeffs_[2], coeffs_[3] + other.coeffs_[3], r_ + other.r_, time_interval_);
00108 }
00109 
00110 TaylorModel TaylorModel::operator - (const TaylorModel& other) const
00111 {
00112   assert(other.time_interval_ == time_interval_);
00113   return TaylorModel(coeffs_[0] - other.coeffs_[0], coeffs_[1] - other.coeffs_[1], coeffs_[2] - other.coeffs_[2], coeffs_[3] - other.coeffs_[3], r_ - other.r_, time_interval_);
00114 }
00115 TaylorModel& TaylorModel::operator += (const TaylorModel& other)
00116 {
00117   assert(other.time_interval_ == time_interval_);
00118   coeffs_[0] += other.coeffs_[0];
00119   coeffs_[1] += other.coeffs_[1];
00120   coeffs_[2] += other.coeffs_[2];
00121   coeffs_[3] += other.coeffs_[3];
00122   r_ += other.r_;
00123   return *this;
00124 }
00125 
00126 TaylorModel& TaylorModel::operator -= (const TaylorModel& other)
00127 {
00128   assert(other.time_interval_ == time_interval_);
00129   coeffs_[0] -= other.coeffs_[0];
00130   coeffs_[1] -= other.coeffs_[1];
00131   coeffs_[2] -= other.coeffs_[2];
00132   coeffs_[3] -= other.coeffs_[3];
00133   r_ -= other.r_;
00134   return *this;
00135 }
00136 
00152 TaylorModel TaylorModel::operator * (const TaylorModel& other) const
00153 {
00154   TaylorModel res(*this);
00155   res *= other;
00156   return res;
00157 }
00158 
00159 TaylorModel TaylorModel::operator * (FCL_REAL d) const
00160 {
00161   return TaylorModel(coeffs_[0] * d, coeffs_[1] * d, coeffs_[2] * d, coeffs_[3] * d,  r_ * d, time_interval_);
00162 }
00163 
00164 TaylorModel& TaylorModel::operator *= (const TaylorModel& other)
00165 {
00166   assert(other.time_interval_ == time_interval_);
00167   register FCL_REAL c0, c1, c2, c3;
00168   register FCL_REAL c0b = other.coeffs_[0], c1b = other.coeffs_[1], c2b = other.coeffs_[2], c3b = other.coeffs_[3];
00169 
00170   const Interval& rb = other.r_;
00171 
00172   c0 = coeffs_[0] * c0b;
00173   c1 = coeffs_[0] * c1b + coeffs_[1] * c0b;
00174   c2 = coeffs_[0] * c2b + coeffs_[1] * c1b + coeffs_[2] * c0b;
00175   c3 = coeffs_[0] * c3b + coeffs_[1] * c2b + coeffs_[2] * c1b + coeffs_[3] * c0b;
00176 
00177   Interval remainder(r_ * rb);
00178   register FCL_REAL tempVal = coeffs_[1] * c3b + coeffs_[2] * c2b + coeffs_[3] * c1b;
00179   remainder += time_interval_->t4_ * tempVal;
00180 
00181   tempVal = coeffs_[2] * c3b + coeffs_[3] * c2b;
00182   remainder += time_interval_->t5_ * tempVal;
00183 
00184   tempVal = coeffs_[3] * c3b;
00185   remainder += time_interval_->t6_ * tempVal;
00186 
00187   remainder += ((Interval(coeffs_[0]) + time_interval_->t_ * coeffs_[1] + time_interval_->t2_ * coeffs_[2] + time_interval_->t3_ * coeffs_[3]) * rb +
00188                 (Interval(c0b) + time_interval_->t_ * c1b + time_interval_->t2_ * c2b + time_interval_->t3_ * c3b) * r_);
00189 
00190   coeffs_[0] = c0;
00191   coeffs_[1] = c1;
00192   coeffs_[2] = c2;
00193   coeffs_[3] = c3;
00194 
00195   r_ = remainder;
00196 
00197   return *this;
00198 }
00199 
00200 TaylorModel& TaylorModel::operator *= (FCL_REAL d)
00201 {
00202   coeffs_[0] *= d;
00203   coeffs_[1] *= d;
00204   coeffs_[2] *= d;
00205   coeffs_[3] *= d;
00206   r_ *= d;
00207   return *this;
00208 }
00209 
00210 
00211 TaylorModel TaylorModel::operator - () const
00212 {
00213   return TaylorModel(-coeffs_[0], -coeffs_[1], -coeffs_[2], -coeffs_[3], -r_, time_interval_);
00214 }
00215 
00216 void TaylorModel::print() const
00217 {
00218   std::cout << coeffs_[0] << "+" << coeffs_[1] << "*t+" << coeffs_[2] << "*t^2+" << coeffs_[3] << "*t^3+[" << r_[0] << "," << r_[1] << "]" << std::endl;
00219 }
00220 
00221 Interval TaylorModel::getBound(FCL_REAL t) const
00222 {
00223   return Interval(coeffs_[0] + t * (coeffs_[1] + t * (coeffs_[2] + t * coeffs_[3]))) + r_;
00224 }
00225 
00226 Interval TaylorModel::getBound(FCL_REAL t0, FCL_REAL t1) const
00227 {
00228   Interval t(t0, t1);
00229   Interval t2(t0 * t0, t1 * t1);
00230   Interval t3(t0 * t2[0], t1 * t2[1]);
00231 
00232   return Interval(coeffs_[0]) + t * coeffs_[1] + t2 * coeffs_[2] + t3 * coeffs_[3] + r_;
00233 }
00234 
00235 Interval TaylorModel::getBound() const
00236 {
00237   return Interval(coeffs_[0] + r_[0], coeffs_[1] + r_[1]) + time_interval_->t_ * coeffs_[1] + time_interval_->t2_ * coeffs_[2] + time_interval_->t3_ * coeffs_[3];
00238 }
00239 
00240 Interval TaylorModel::getTightBound(FCL_REAL t0, FCL_REAL t1) const
00241 {
00242   if(t0 < time_interval_->t_[0]) t0 = time_interval_->t_[0];
00243   if(t1 > time_interval_->t_[1]) t1 = time_interval_->t_[1];
00244 
00245   if(coeffs_[3] == 0)
00246   {
00247     register FCL_REAL a = -coeffs_[1] / (2 * coeffs_[2]);
00248     Interval polybounds;
00249     if(a <= t1 && a >= t0)
00250     {
00251       FCL_REAL AQ = coeffs_[0] + a * (coeffs_[1] + a * coeffs_[2]);
00252       register FCL_REAL t = t0;
00253       FCL_REAL LQ = coeffs_[0] + t * (coeffs_[1] + t * coeffs_[2]);
00254       t = t1;
00255       FCL_REAL RQ = coeffs_[0] + t * (coeffs_[1] + t * coeffs_[2]);
00256 
00257       FCL_REAL minQ = LQ, maxQ = RQ;
00258       if(LQ > RQ)
00259       {
00260         minQ = RQ;
00261         maxQ = LQ;
00262       }
00263 
00264       if(minQ > AQ) minQ = AQ;
00265       if(maxQ < AQ) maxQ = AQ;
00266 
00267       polybounds.setValue(minQ, maxQ);
00268     }
00269     else
00270     {
00271       register FCL_REAL t = t0;
00272       FCL_REAL LQ = coeffs_[0] + t * (coeffs_[1] + t * coeffs_[2]);
00273       t = t1;
00274       FCL_REAL RQ = coeffs_[0] + t * (coeffs_[1] + t * coeffs_[2]);
00275 
00276       if(LQ > RQ) polybounds.setValue(RQ, LQ);
00277       else polybounds.setValue(LQ, RQ);
00278     }
00279 
00280     return polybounds + r_;
00281   }
00282   else
00283   {
00284     register FCL_REAL t = t0;
00285     FCL_REAL LQ = coeffs_[0] + t * (coeffs_[1] + t * (coeffs_[2] + t * coeffs_[3]));
00286     t = t1;
00287     FCL_REAL RQ = coeffs_[0] + t * (coeffs_[1] + t * (coeffs_[2] + t * coeffs_[3]));
00288 
00289     if(LQ > RQ)
00290     {
00291       FCL_REAL tmp = LQ;
00292       LQ = RQ;
00293       RQ = tmp;
00294     }
00295 
00296     // derivative: c1+2*c2*t+3*c3*t^2
00297 
00298     FCL_REAL delta = coeffs_[2] * coeffs_[2] - 3 * coeffs_[1] * coeffs_[3];
00299     if(delta < 0)
00300       return Interval(LQ, RQ) + r_;
00301 
00302     FCL_REAL r1 = (-coeffs_[2]-sqrt(delta))/(3*coeffs_[3]);
00303     FCL_REAL r2 = (-coeffs_[2]+sqrt(delta))/(3*coeffs_[3]);
00304 
00305     if(r1 <= t1 && r1 >= t0)
00306     {
00307       FCL_REAL Q = coeffs_[0] + r1 * (coeffs_[1] + r1 * (coeffs_[2] + r1 * coeffs_[3]));
00308       if(Q < LQ) LQ = Q;
00309       else if(Q > RQ) RQ = Q;
00310     }
00311 
00312     if(r2 <= t1 && r2 >= t0)
00313     {
00314       FCL_REAL Q = coeffs_[0] + r2 * (coeffs_[1] + r2 * (coeffs_[2] + r2 * coeffs_[3]));
00315       if(Q < LQ) LQ = Q;
00316       else if(Q > RQ) RQ = Q;
00317     }
00318 
00319     return Interval(LQ, RQ) + r_;
00320   }
00321 }
00322 
00323 Interval TaylorModel::getTightBound() const
00324 {
00325   return getTightBound(time_interval_->t_[0], time_interval_->t_[1]);
00326 }
00327 
00328 void TaylorModel::setZero()
00329 {
00330   coeffs_[0] = coeffs_[1] = coeffs_[2] = coeffs_[3] = 0;
00331   r_.setValue(0);
00332 }
00333 
00334 
00335 void generateTaylorModelForCosFunc(TaylorModel& tm, FCL_REAL w, FCL_REAL q0)
00336 {
00337   FCL_REAL a = tm.time_interval_->t_.center();
00338   FCL_REAL t = w * a + q0;
00339   FCL_REAL w2 = w * w;
00340   FCL_REAL fa = cos(t);
00341   FCL_REAL fda = -w*sin(t);
00342   FCL_REAL fdda = -w2*fa;
00343   FCL_REAL fddda = -w2*fda;
00344 
00345   tm.coeffs_[0] = fa-a*(fda-0.5*a*(fdda-1.0/3.0*a*fddda));
00346   tm.coeffs_[1] = fda-a*fdda+0.5*a*a*fddda;
00347   tm.coeffs_[2] = 0.5*(fdda-a*fddda);
00348   tm.coeffs_[3] = 1.0/6.0*fddda;
00349 
00350   // compute bounds for w^3 cos(wt+q0)/16, t \in [t0, t1]
00351   Interval fddddBounds;
00352   if(w == 0) fddddBounds.setValue(0);
00353   else
00354   {
00355     FCL_REAL cosQL = cos(tm.time_interval_->t_[0] * w + q0);
00356     FCL_REAL cosQR = cos(tm.time_interval_->t_[1] * w + q0);
00357 
00358     if(cosQL < cosQR) fddddBounds.setValue(cosQL, cosQR);
00359     else fddddBounds.setValue(cosQR, cosQL);
00360 
00361     // enlarge to handle round-off errors
00362     fddddBounds[0] -= 1e-15;
00363     fddddBounds[1] += 1e-15;
00364 
00365     // cos reaches maximum if there exists an integer k in [(w*t0+q0)/2pi, (w*t1+q0)/2pi];
00366     // cos reaches minimum if there exists an integer k in [(w*t0+q0-pi)/2pi, (w*t1+q0-pi)/2pi]
00367 
00368     FCL_REAL k1 = (tm.time_interval_->t_[0] * w + q0) / (2 * boost::math::constants::pi<FCL_REAL>());
00369     FCL_REAL k2 = (tm.time_interval_->t_[1] * w + q0) / (2 * boost::math::constants::pi<FCL_REAL>());
00370 
00371 
00372     if(w > 0)
00373     {
00374       if(ceil(k2) - floor(k1) > 1) fddddBounds[1] = 1;
00375       k1 -= 0.5;
00376       k2 -= 0.5;
00377       if(ceil(k2) - floor(k1) > 1) fddddBounds[0] = -1;
00378     }
00379     else
00380     {
00381       if(ceil(k1) - floor(k2) > 1) fddddBounds[1] = 1;
00382       k1 -= 0.5;
00383       k2 -= 0.5;
00384       if(ceil(k1) - floor(k2) > 1) fddddBounds[0] = -1;
00385     }
00386   }
00387 
00388   FCL_REAL w4 = w2 * w2;
00389   fddddBounds *= w4;
00390 
00391   FCL_REAL midSize = 0.5 * (tm.time_interval_->t_[1] - tm.time_interval_->t_[0]);
00392   FCL_REAL midSize2 = midSize * midSize;
00393   FCL_REAL midSize4 = midSize2 * midSize2;
00394 
00395   // [0, midSize4] * fdddBounds
00396   if(fddddBounds[0] > 0)
00397     tm.r_.setValue(0, fddddBounds[1] * midSize4 * (1.0 / 24));
00398   else if(fddddBounds[0] < 0)
00399     tm.r_.setValue(fddddBounds[0] * midSize4 * (1.0 / 24), 0);
00400   else
00401     tm.r_.setValue(fddddBounds[0] * midSize4 * (1.0 / 24), fddddBounds[1] * midSize4 * (1.0 / 24));
00402 }
00403 
00404 void generateTaylorModelForSinFunc(TaylorModel& tm, FCL_REAL w, FCL_REAL q0)
00405 {
00406   FCL_REAL a = tm.time_interval_->t_.center();
00407   FCL_REAL t = w * a + q0;
00408   FCL_REAL w2 = w * w;
00409   FCL_REAL fa = sin(t);
00410   FCL_REAL fda = w*cos(t);
00411   FCL_REAL fdda = -w2*fa;
00412   FCL_REAL fddda = -w2*fda;
00413 
00414   tm.coeffs_[0] = fa-a*(fda-0.5*a*(fdda-1.0/3.0*a*fddda));
00415   tm.coeffs_[1] = fda-a*fdda+0.5*a*a*fddda;
00416   tm.coeffs_[2] = 0.5*(fdda-a*fddda);
00417   tm.coeffs_[3] = 1.0/6.0*fddda;
00418 
00419   // compute bounds for w^3 sin(wt+q0)/16, t \in [t0, t1]
00420 
00421   Interval fddddBounds;
00422 
00423   if(w == 0) fddddBounds.setValue(0);
00424   else
00425   {
00426     FCL_REAL sinQL = sin(w * tm.time_interval_->t_[0] + q0);
00427     FCL_REAL sinQR = sin(w * tm.time_interval_->t_[1] + q0);
00428 
00429     if(sinQL < sinQR) fddddBounds.setValue(sinQL, sinQR);
00430     else fddddBounds.setValue(sinQR, sinQL);
00431 
00432     // enlarge to handle round-off errors
00433     fddddBounds[0] -= 1e-15;
00434     fddddBounds[1] += 1e-15;
00435 
00436     // sin reaches maximum if there exists an integer k in [(w*t0+q0-pi/2)/2pi, (w*t1+q0-pi/2)/2pi];
00437     // sin reaches minimum if there exists an integer k in [(w*t0+q0-pi-pi/2)/2pi, (w*t1+q0-pi-pi/2)/2pi]
00438 
00439     FCL_REAL k1 = (tm.time_interval_->t_[0] * w + q0) / (2 * boost::math::constants::pi<FCL_REAL>()) - 0.25;
00440     FCL_REAL k2 = (tm.time_interval_->t_[1] * w + q0) / (2 * boost::math::constants::pi<FCL_REAL>()) - 0.25;
00441 
00442     if(w > 0)
00443     {
00444       if(ceil(k2) - floor(k1) > 1) fddddBounds[1] = 1;
00445       k1 -= 0.5;
00446       k2 -= 0.5;
00447       if(ceil(k2) - floor(k1) > 1) fddddBounds[0] = -1;
00448     }
00449     else
00450     {
00451       if(ceil(k1) - floor(k2) > 1) fddddBounds[1] = 1;
00452       k1 -= 0.5;
00453       k2 -= 0.5;
00454       if(ceil(k1) - floor(k2) > 1) fddddBounds[0] = -1;
00455     }
00456 
00457     FCL_REAL w4 = w2 * w2;
00458     fddddBounds *= w4;
00459 
00460     FCL_REAL midSize = 0.5 * (tm.time_interval_->t_[1] - tm.time_interval_->t_[0]);
00461     FCL_REAL midSize2 = midSize * midSize;
00462     FCL_REAL midSize4 = midSize2 * midSize2;
00463 
00464     // [0, midSize4] * fdddBounds
00465     if(fddddBounds[0] > 0)
00466       tm.r_.setValue(0, fddddBounds[1] * midSize4 * (1.0 / 24));
00467     else if(fddddBounds[0] < 0)
00468       tm.r_.setValue(fddddBounds[0] * midSize4 * (1.0 / 24), 0);
00469     else
00470       tm.r_.setValue(fddddBounds[0] * midSize4 * (1.0 / 24), fddddBounds[1] * midSize4 * (1.0 / 24));
00471   }
00472 }
00473 
00474 void generateTaylorModelForLinearFunc(TaylorModel& tm, FCL_REAL p, FCL_REAL v)
00475 {
00476   tm.coeffs_[0] = p;
00477   tm.coeffs_[1] = v;
00478   tm.coeffs_[2] = tm.coeffs_[3] = tm.r_[0] = tm.r_[1] = 0;
00479 }
00480 
00481 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:30