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 #ifndef ROS_TIME_H_
00019 #define ROS_TIME_H_
00020
00021 #include <math.h>
00022 #include <stdint.h>
00023
00024 #include "ros/duration.h"
00025
00026 namespace ros
00027 {
00028 void normalizeSecNSec(uint32_t &sec, uint32_t &nsec);
00029
00030 class Time
00031 {
00032 public:
00033 uint32_t sec, nsec;
00034
00035 Time() : sec(0), nsec(0) {}
00036 Time(uint32_t _sec, uint32_t _nsec) : sec(_sec), nsec(_nsec)
00037 {
00038 normalizeSecNSec(sec, nsec);
00039 }
00040
00041 double toSec() const { return (double)sec + 1e-9*(double)nsec; };
00042 void fromSec(double t) { sec = (uint32_t) floor(t); nsec = (uint32_t) round((t-sec) * 1e9); };
00043
00044 uint32_t toNsec() { return (uint32_t)sec*1000000000ull + (uint32_t)nsec; };
00045 Time& fromNSec(int32_t t);
00046
00047 Time& operator +=(const Duration &rhs);
00048 Time& operator -=(const Duration &rhs);
00049
00050 static Time now();
00051 static void setNow( Time & new_now);
00052 };
00053
00054 }
00055
00056 #endif