duration.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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 #ifndef ROSTIME_IMPL_DURATION_H_INCLUDED
00035 #define ROSTIME_IMPL_DURATION_H_INCLUDED
00036 
00037 #include <ros/duration.h>
00038 #include <ros/rate.h>
00039 #include <boost/date_time/posix_time/posix_time_types.hpp>
00040 
00041 namespace ros {
00042   //
00043   // DurationBase template member function implementation
00044   //
00045   template<class T>
00046   DurationBase<T>::DurationBase(int32_t _sec, int32_t _nsec)
00047   : sec(_sec), nsec(_nsec)
00048   {
00049     normalizeSecNSecSigned(sec, nsec);
00050   }
00051 
00052   template<class T>
00053   T& DurationBase<T>::fromSec(double d)
00054   {
00055     sec = (int32_t)floor(d);
00056     nsec = (int32_t)((d - (double)sec)*1000000000);
00057     return *static_cast<T*>(this);
00058   }
00059 
00060   template<class T>
00061   T& DurationBase<T>::fromNSec(int64_t t)
00062   {
00063     sec  = (int32_t)(t / 1000000000);
00064     nsec = (int32_t)(t % 1000000000);
00065 
00066     normalizeSecNSecSigned(sec, nsec);
00067 
00068     return *static_cast<T*>(this);
00069   }
00070 
00071   template<class T>
00072   T DurationBase<T>::operator+(const T &rhs) const
00073   {
00074     return T(sec + rhs.sec, nsec + rhs.nsec);
00075   }
00076 
00077   template<class T>
00078   T DurationBase<T>::operator*(double scale) const
00079   {
00080     return T(toSec() * scale);
00081   }
00082 
00083   template<class T>
00084   T DurationBase<T>::operator-(const T &rhs) const
00085   {
00086     return T(sec - rhs.sec, nsec - rhs.nsec);
00087   }
00088 
00089   template<class T>
00090   T DurationBase<T>::operator-() const
00091   {
00092     return T(-sec , -nsec);
00093   }
00094 
00095   template<class T>
00096   T& DurationBase<T>::operator+=(const T &rhs)
00097   {
00098     *this = *this + rhs;
00099     return *static_cast<T*>(this);
00100   }
00101 
00102   template<class T>
00103   T& DurationBase<T>::operator-=(const T &rhs)
00104   {
00105     *this += (-rhs);
00106     return *static_cast<T*>(this);
00107   }
00108 
00109   template<class T>
00110   T& DurationBase<T>::operator*=(double scale)
00111   {
00112     fromSec(toSec() * scale);
00113     return *static_cast<T*>(this);
00114   }
00115 
00116   template<class T>
00117   bool DurationBase<T>::operator<(const T &rhs) const
00118   {
00119     if (sec < rhs.sec)
00120       return true;
00121     else if (sec == rhs.sec && nsec < rhs.nsec)
00122       return true;
00123     return false;
00124   }
00125 
00126   template<class T>
00127   bool DurationBase<T>::operator>(const T &rhs) const
00128   {
00129     if (sec > rhs.sec)
00130       return true;
00131     else if (sec == rhs.sec && nsec > rhs.nsec)
00132       return true;
00133     return false;
00134   }
00135 
00136   template<class T>
00137   bool DurationBase<T>::operator<=(const T &rhs) const
00138   {
00139     if (sec < rhs.sec)
00140       return true;
00141     else if (sec == rhs.sec && nsec <= rhs.nsec)
00142       return true;
00143     return false;
00144   }
00145 
00146   template<class T>
00147   bool DurationBase<T>::operator>=(const T &rhs) const
00148   {
00149     if (sec > rhs.sec)
00150       return true;
00151     else if (sec == rhs.sec && nsec >= rhs.nsec)
00152       return true;
00153     return false;
00154   }
00155 
00156   template<class T>
00157   bool DurationBase<T>::operator==(const T &rhs) const
00158   {
00159     return sec == rhs.sec && nsec == rhs.nsec;
00160   }
00161 
00162   template<class T>
00163   bool DurationBase<T>::isZero() const
00164   {
00165     return sec == 0 && nsec == 0;
00166   }
00167 
00168   template <class T>
00169   boost::posix_time::time_duration
00170   DurationBase<T>::toBoost() const
00171   {
00172     namespace bt = boost::posix_time;
00173 #if defined(BOOST_DATE_TIME_HAS_NANOSECONDS)
00174     return bt::seconds(sec) + bt::nanoseconds(nsec);
00175 #else
00176     return bt::seconds(sec) + bt::microseconds(nsec/1000.0);
00177 #endif
00178   }
00179 }
00180 #endif


rostime
Author(s): Josh Faust
autogenerated on Sat Jun 8 2019 20:30:24