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
00031
00032
00033
00034
00035 #ifndef ROS_DURATION_H
00036 #define ROS_DURATION_H
00037
00038
00039
00040
00041
00042 #ifdef _MSC_VER
00043
00044
00045 #pragma warning(disable: 4244)
00046 #pragma warning(disable: 4661)
00047 #endif
00048
00049 #include <iostream>
00050 #include <math.h>
00051 #include <stdexcept>
00052 #include <climits>
00053 #include <stdint.h>
00054 #include "rostime_decl.h"
00055
00056 namespace boost {
00057 namespace posix_time {
00058 class time_duration;
00059 }
00060 }
00061
00062 namespace ros
00063 {
00064 ROSTIME_DECL void normalizeSecNSecSigned(int64_t& sec, int64_t& nsec);
00065 ROSTIME_DECL void normalizeSecNSecSigned(int32_t& sec, int32_t& nsec);
00066
00071 template <class T>
00072 class DurationBase
00073 {
00074 public:
00075 int32_t sec, nsec;
00076 DurationBase() : sec(0), nsec(0) { }
00077 DurationBase(int32_t _sec, int32_t _nsec);
00078 explicit DurationBase(double t){fromSec(t);};
00079 ~DurationBase() {}
00080 T operator+(const T &rhs) const;
00081 T operator-(const T &rhs) const;
00082 T operator-() const;
00083 T operator*(double scale) const;
00084 T& operator+=(const T &rhs);
00085 T& operator-=(const T &rhs);
00086 T& operator*=(double scale);
00087 bool operator==(const T &rhs) const;
00088 inline bool operator!=(const T &rhs) const { return !(*static_cast<const T*>(this) == rhs); }
00089 bool operator>(const T &rhs) const;
00090 bool operator<(const T &rhs) const;
00091 bool operator>=(const T &rhs) const;
00092 bool operator<=(const T &rhs) const;
00093 double toSec() const { return (double)sec + 1e-9*(double)nsec; };
00094 int64_t toNSec() const {return (int64_t)sec*1000000000ll + (int64_t)nsec; };
00095 T& fromSec(double t);
00096 T& fromNSec(int64_t t);
00097 bool isZero() const;
00098 boost::posix_time::time_duration toBoost() const;
00099 };
00100
00101 class Rate;
00102
00108 class ROSTIME_DECL Duration : public DurationBase<Duration>
00109 {
00110 public:
00111 Duration()
00112 : DurationBase<Duration>()
00113 { }
00114
00115 Duration(int32_t _sec, int32_t _nsec)
00116 : DurationBase<Duration>(_sec, _nsec)
00117 {}
00118
00119 explicit Duration(double t) { fromSec(t); }
00120 explicit Duration(const Rate&);
00124 bool sleep() const;
00125 };
00126
00127 extern ROSTIME_DECL const Duration DURATION_MAX;
00128 extern ROSTIME_DECL const Duration DURATION_MIN;
00129
00135 class ROSTIME_DECL WallDuration : public DurationBase<WallDuration>
00136 {
00137 public:
00138 WallDuration()
00139 : DurationBase<WallDuration>()
00140 { }
00141
00142 WallDuration(int32_t _sec, int32_t _nsec)
00143 : DurationBase<WallDuration>(_sec, _nsec)
00144 {}
00145
00146 explicit WallDuration(double t) { fromSec(t); }
00147 explicit WallDuration(const Rate&);
00151 bool sleep() const;
00152 };
00153
00154 std::ostream &operator <<(std::ostream &os, const Duration &rhs);
00155 std::ostream &operator <<(std::ostream &os, const WallDuration &rhs);
00156
00157
00158 }
00159
00160 #endif // ROS_DURATION_H
00161
00162