Go to the documentation of this file.00001 #include <ros/duration.h>
00002 #include <ros/impl/duration.h>
00003
00004 namespace ros {
00005
00006 void normalizeSecNSecSigned(int64_t& sec, int64_t& nsec)
00007 {
00008 int64_t nsec_part = nsec % 1000000000L;
00009 int64_t sec_part = sec + nsec / 1000000000L;
00010 if (nsec_part < 0)
00011 {
00012 nsec_part += 1000000000L;
00013 --sec_part;
00014 }
00015
00016 if (sec_part < INT_MIN || sec_part > INT_MAX)
00017 throw std::runtime_error("Duration is out of dual 32-bit range");
00018
00019 sec = sec_part;
00020 nsec = nsec_part;
00021 }
00022
00023 void normalizeSecNSecSigned(int32_t& sec, int32_t& nsec)
00024 {
00025 int64_t sec64 = sec;
00026 int64_t nsec64 = nsec;
00027
00028 normalizeSecNSecSigned(sec64, nsec64);
00029
00030 sec = (int32_t)sec64;
00031 nsec = (int32_t)nsec64;
00032 }
00033
00034 template class DurationBase<Duration>;
00035 template class DurationBase<WallDuration>;
00036 }
00037