34 #ifndef ROSTIME_IMPL_DURATION_H_INCLUDED 35 #define ROSTIME_IMPL_DURATION_H_INCLUDED 39 #include <boost/date_time/posix_time/posix_time_types.hpp> 40 #include <boost/math/special_functions/round.hpp> 48 : sec(_sec), nsec(_nsec)
56 int64_t sec64 =
static_cast<int64_t
>(floor(d));
57 if (sec64 < std::numeric_limits<int32_t>::min() || sec64 > std::numeric_limits<int32_t>::max())
58 throw std::runtime_error(
"Duration is out of dual 32-bit range");
59 sec =
static_cast<int32_t
>(sec64);
60 nsec =
static_cast<int32_t
>(boost::math::round((d - sec) * 1e9));
61 int32_t rollover = nsec / 1000000000ul;
64 return *
static_cast<T*
>(
this);
70 int64_t sec64 = t / 1000000000LL;
71 if (sec64 < std::numeric_limits<int32_t>::min() || sec64 > std::numeric_limits<int32_t>::max())
72 throw std::runtime_error(
"Duration is out of dual 32-bit range");
73 sec =
static_cast<int32_t
>(sec64);
74 nsec =
static_cast<int32_t
>(t % 1000000000LL);
78 return *
static_cast<T*
>(
this);
85 return t.
fromNSec(toNSec() + rhs.toNSec());
91 return T(toSec() * scale);
98 return t.
fromNSec(toNSec() - rhs.toNSec());
112 return *
static_cast<T*
>(
this);
119 return *
static_cast<T*
>(
this);
125 fromSec(toSec() * scale);
126 return *
static_cast<T*
>(
this);
134 else if (sec == rhs.sec && nsec < rhs.nsec)
144 else if (sec == rhs.sec && nsec > rhs.nsec)
154 else if (sec == rhs.sec && nsec <= rhs.nsec)
164 else if (sec == rhs.sec && nsec >= rhs.nsec)
172 return sec == rhs.
sec && nsec == rhs.nsec;
178 return sec == 0 && nsec == 0;
182 boost::posix_time::time_duration
186 #if defined(BOOST_DATE_TIME_HAS_NANOSECONDS) 187 return bt::seconds(sec) + bt::nanoseconds(nsec);
189 return bt::seconds(sec) + bt::microseconds(nsec/1000);
ROSTIME_DECL void normalizeSecNSecSigned(int64_t &sec, int64_t &nsec)
Base class for Duration implementations. Provides storage, common functions and operator overloads...