$search
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 00035 #ifndef ROS_TIME_H_INCLUDED 00036 #define ROS_TIME_H_INCLUDED 00037 00038 /********************************************************************* 00039 ** Pragmas 00040 *********************************************************************/ 00041 00042 #ifdef _MSC_VER 00043 // Rostime has some magic interface that doesn't directly include 00044 // its implementation, this just disables those warnings. 00045 #pragma warning(disable: 4244) 00046 #pragma warning(disable: 4661) 00047 #endif 00048 00049 /********************************************************************* 00050 ** Headers 00051 *********************************************************************/ 00052 00053 #include <ros/platform.h> 00054 #include <iostream> 00055 #include <cmath> 00056 #include <ros/exception.h> 00057 #include "duration.h" 00058 #include <boost/math/special_functions/round.hpp> 00059 #include "rostime_decl.h" 00060 00061 /********************************************************************* 00062 ** Cross Platform Headers 00063 *********************************************************************/ 00064 00065 #ifdef WIN32 00066 #include <sys/timeb.h> 00067 #else 00068 #include <sys/time.h> 00069 #endif 00070 00071 namespace boost { 00072 namespace posix_time { 00073 class ptime; 00074 } 00075 } 00076 00077 namespace ros 00078 { 00079 00080 /********************************************************************* 00081 ** Exceptions 00082 *********************************************************************/ 00083 00087 class ROSTIME_DECL TimeNotInitializedException : public Exception 00088 { 00089 public: 00090 TimeNotInitializedException() 00091 : Exception("Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called. " 00092 "If this is a standalone app or test that just uses ros::Time and does not communicate over ROS, you may also call ros::Time::init()") 00093 {} 00094 }; 00095 00101 class ROSTIME_DECL NoHighPerformanceTimersException : public Exception 00102 { 00103 public: 00104 NoHighPerformanceTimersException() 00105 : Exception("This windows platform does not " 00106 "support the high-performance timing api.") 00107 {} 00108 }; 00109 00110 /********************************************************************* 00111 ** Functions 00112 *********************************************************************/ 00113 00114 ROSTIME_DECL void normalizeSecNSec(uint64_t& sec, uint64_t& nsec); 00115 ROSTIME_DECL void normalizeSecNSec(uint32_t& sec, uint32_t& nsec); 00116 ROSTIME_DECL void normalizeSecNSecUnsigned(int64_t& sec, int64_t& nsec); 00117 00118 /********************************************************************* 00119 ** Time Classes 00120 *********************************************************************/ 00121 00126 template<class T, class D> 00127 class TimeBase 00128 { 00129 public: 00130 uint32_t sec, nsec; 00131 00132 TimeBase() : sec(0), nsec(0) { } 00133 TimeBase(uint32_t _sec, uint32_t _nsec) : sec(_sec), nsec(_nsec) 00134 { 00135 normalizeSecNSec(sec, nsec); 00136 } 00137 explicit TimeBase(double t) { fromSec(t); } 00138 ~TimeBase() {} 00139 D operator-(const T &rhs) const; 00140 T operator+(const D &rhs) const; 00141 T operator-(const D &rhs) const; 00142 T& operator+=(const D &rhs); 00143 T& operator-=(const D &rhs); 00144 bool operator==(const T &rhs) const; 00145 inline bool operator!=(const T &rhs) const { return !(*static_cast<const T*>(this) == rhs); } 00146 bool operator>(const T &rhs) const; 00147 bool operator<(const T &rhs) const; 00148 bool operator>=(const T &rhs) const; 00149 bool operator<=(const T &rhs) const; 00150 00151 double toSec() const { return (double)sec + 1e-9*(double)nsec; }; 00152 T& fromSec(double t) { sec = (uint32_t)floor(t); nsec = (uint32_t)boost::math::round((t-sec) * 1e9); return *static_cast<T*>(this);} 00153 00154 uint64_t toNSec() const {return (uint64_t)sec*1000000000ull + (uint64_t)nsec; } 00155 T& fromNSec(uint64_t t); 00156 00157 inline bool isZero() const { return sec == 0 && nsec == 0; } 00158 inline bool is_zero() const { return isZero(); } 00159 boost::posix_time::ptime toBoost() const; 00160 00161 }; 00162 00168 class ROSTIME_DECL Time : public TimeBase<Time, Duration> 00169 { 00170 public: 00171 Time() 00172 : TimeBase<Time, Duration>() 00173 {} 00174 00175 Time(uint32_t _sec, uint32_t _nsec) 00176 : TimeBase<Time, Duration>(_sec, _nsec) 00177 {} 00178 00179 explicit Time(double t) { fromSec(t); } 00180 00185 static Time now(); 00189 static bool sleepUntil(const Time& end); 00190 00191 static void init(); 00192 static void shutdown(); 00193 static void setNow(const Time& new_now); 00194 static bool useSystemTime(); 00195 static bool isSimTime(); 00196 static bool isSystemTime(); 00197 00201 static bool isValid(); 00205 static bool waitForValid(); 00209 static bool waitForValid(const ros::WallDuration& timeout); 00210 }; 00211 00212 extern const Time TIME_MAX; 00213 extern const Time TIME_MIN; 00214 00220 class ROSTIME_DECL WallTime : public TimeBase<WallTime, WallDuration> 00221 { 00222 public: 00223 WallTime() 00224 : TimeBase<WallTime, WallDuration>() 00225 {} 00226 00227 WallTime(uint32_t _sec, uint32_t _nsec) 00228 : TimeBase<WallTime, WallDuration>(_sec, _nsec) 00229 {} 00230 00231 explicit WallTime(double t) { fromSec(t); } 00232 00236 static WallTime now(); 00237 00241 static bool sleepUntil(const WallTime& end); 00242 00243 static bool isSystemTime() { return true; } 00244 }; 00245 00246 ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const Time &rhs); 00247 ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const WallTime &rhs); 00248 } 00249 00250 #endif // ROS_TIME_H 00251