Goby v2
time.h
1 // Copyright 2009-2018 Toby Schneider (http://gobysoft.org/index.wt/people/toby)
2 // GobySoft, LLC (2013-)
3 // Massachusetts Institute of Technology (2007-2014)
4 // Community contributors (see AUTHORS file)
5 //
6 //
7 // This file is part of the Goby Underwater Autonomy Project Libraries
8 // ("The Goby Libraries").
9 //
10 // The Goby Libraries are free software: you can redistribute them and/or modify
11 // them under the terms of the GNU Lesser General Public License as published by
12 // the Free Software Foundation, either version 2.1 of the License, or
13 // (at your option) any later version.
14 //
15 // The Goby Libraries are distributed in the hope that they will be useful,
16 // but WITHOUT ANY WARRANTY; without even the implied warranty of
17 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18 // GNU Lesser General Public License for more details.
19 //
20 // You should have received a copy of the GNU Lesser General Public License
21 // along with Goby. If not, see <http://www.gnu.org/licenses/>.
22 
23 #ifndef Time20100713H
24 #define Time20100713H
25 
26 #include <ctime>
27 #include <sys/time.h>
28 
29 #include <boost/asio/time_traits.hpp>
30 #include <boost/date_time.hpp>
31 #include <boost/function.hpp>
32 #include <boost/static_assert.hpp>
33 
34 #include "goby/util/as.h"
35 #include "goby/util/primitive_types.h"
36 
38 namespace goby
39 {
40 namespace common
41 {
43 double ptime2unix_double(boost::posix_time::ptime given_time);
44 
46 boost::posix_time::ptime unix_double2ptime(double given_time);
47 
49 uint64 ptime2unix_microsec(boost::posix_time::ptime given_time);
50 
52 boost::posix_time::ptime unix_microsec2ptime(uint64 given_time);
53 } // namespace common
54 
55 namespace util
56 {
58 template <typename To, typename From>
59 typename boost::enable_if<
60  boost::mpl::and_<boost::is_same<To, double>, boost::is_same<From, boost::posix_time::ptime> >,
61  To>::type
62 as(const From& from)
63 {
65 }
66 
68 template <typename To, typename From>
69 typename boost::enable_if<
70  boost::mpl::and_<boost::is_same<To, boost::posix_time::ptime>, boost::is_same<From, double> >,
71  To>::type
72 as(const From& from)
73 {
75 }
76 
78 template <typename To, typename From>
79 typename boost::enable_if<
80  boost::mpl::and_<boost::is_same<To, uint64>, boost::is_same<From, boost::posix_time::ptime> >,
81  To>::type
82 as(const From& from)
83 {
85 }
86 
88 template <typename To, typename From>
89 typename boost::enable_if<
90  boost::mpl::and_<boost::is_same<To, boost::posix_time::ptime>, boost::is_same<From, uint64> >,
91  To>::type
92 as(const From& from)
93 {
95 }
96 } // namespace util
97 
99 namespace common
100 {
102 
103 
104 template <typename ReturnType> ReturnType goby_time()
105 {
106  BOOST_STATIC_ASSERT(sizeof(ReturnType) == 0);
107 }
108 
109 extern boost::function0<uint64> goby_time_function;
110 extern int goby_time_warp_factor;
111 
113 template <> inline uint64 goby_time<uint64>()
114 {
115  if (!goby_time_function)
116  {
117  timeval t;
118  gettimeofday(&t, 0);
119  uint64 whole = t.tv_sec;
120  uint64 micro = t.tv_usec;
121  return whole * 1000000 + micro;
122  }
123  else
124  {
125  return goby_time_function();
126  }
127 }
128 
130 template <> inline double goby_time<double>()
131 {
132  return static_cast<double>(goby_time<uint64>()) / 1.0e6;
133 }
134 
135 template <> inline boost::posix_time::ptime goby_time<boost::posix_time::ptime>()
136 {
137  return util::as<boost::posix_time::ptime>(goby_time<uint64>());
138 }
139 
141 inline boost::posix_time::ptime goby_time() { return goby_time<boost::posix_time::ptime>(); }
142 
144 template <> inline std::string goby_time<std::string>()
145 {
146  return goby::util::as<std::string>(goby_time<boost::posix_time::ptime>());
147 }
148 
150 inline std::string goby_time_as_string(const boost::posix_time::ptime& t = goby_time())
151 {
152  return goby::util::as<std::string>(t);
153 }
154 
156 inline std::string goby_file_timestamp()
157 {
158  using namespace boost::posix_time;
159  return to_iso_string(second_clock::universal_time());
160 }
161 
163 inline boost::posix_time::ptime time_t2ptime(std::time_t t)
164 {
165  return boost::posix_time::from_time_t(t);
166 }
167 
169 inline std::time_t ptime2time_t(boost::posix_time::ptime t)
170 {
171  std::tm out = boost::posix_time::to_tm(t);
172  return mktime(&out);
173 }
174 
176 inline double time_duration2double(boost::posix_time::time_duration time_of_day)
177 {
178  using namespace boost::posix_time;
179 
180  // prevent overflows in getting total seconds with call to ptime::total_seconds
181  if (time_of_day.hours() > (0x7FFFFFFF / 3600))
182  return std::numeric_limits<double>::infinity();
183  else
184  return (double(time_of_day.total_seconds()) +
185  double(time_of_day.fractional_seconds()) /
186  double(time_duration::ticks_per_second()));
187 }
188 
190 
191 inline boost::posix_time::ptime nmea_time2ptime(const std::string& mt)
192 {
193  using namespace boost::posix_time;
194  using namespace boost::gregorian;
195 
196  std::string::size_type dot_pos = mt.find('.');
197 
198  // must be at least HHMMSS
199  if (mt.length() < 6)
200  return ptime(not_a_date_time);
201  else
202  {
203  std::string s_fs = "0";
204  // has some fractional seconds
205  if (dot_pos != std::string::npos)
206  s_fs = mt.substr(dot_pos + 1); // everything after the "."
207  else
208  dot_pos = mt.size();
209 
210  std::string s_hour = mt.substr(dot_pos - 6, 2), s_min = mt.substr(dot_pos - 4, 2),
211  s_sec = mt.substr(dot_pos - 2, 2);
212 
213  try
214  {
215  int hour = boost::lexical_cast<int>(s_hour);
216  int min = boost::lexical_cast<int>(s_min);
217  int sec = boost::lexical_cast<int>(s_sec);
218  int micro_sec = boost::lexical_cast<int>(s_fs) * pow(10, 6 - s_fs.size());
219 
220  boost::gregorian::date return_date(boost::gregorian::day_clock::universal_day());
221  boost::posix_time::time_duration return_duration(
222  boost::posix_time::time_duration(hour, min, sec, 0) + microseconds(micro_sec));
223  boost::posix_time::ptime return_time(return_date, return_duration);
224  return return_time;
225  }
226  catch (boost::bad_lexical_cast&)
227  {
228  return ptime(not_a_date_time);
229  }
230  }
231 }
232 
233 // dummy struct for use with boost::asio::time_traits
234 struct GobyTime
235 {
236 };
237 
238 } // namespace common
239 } // namespace goby
240 
241 namespace boost
242 {
243 namespace asio
244 {
246 template <> struct time_traits<goby::common::GobyTime>
247 {
249  typedef boost::posix_time::ptime time_type;
250 
252  typedef boost::posix_time::time_duration duration_type;
253 
255  static time_type now() { return goby::common::goby_time(); }
256 
258  static time_type add(const time_type& t, const duration_type& d) { return t + d; }
259 
261  static duration_type subtract(const time_type& t1, const time_type& t2) { return t1 - t2; }
262 
264  static bool less_than(const time_type& t1, const time_type& t2) { return t1 < t2; }
265 
267  static boost::posix_time::time_duration to_posix_duration(const duration_type& d)
268  {
269  return d / goby::common::goby_time_warp_factor;
270  }
271 };
272 } // namespace asio
273 } // namespace boost
274 
275 #endif
uint64 goby_time< uint64 >()
Returns current UTC time as integer microseconds since 1970-01-01 00:00:00.
Definition: time.h:113
Definition: time.h:241
boost::posix_time::ptime time_t2ptime(std::time_t t)
convert to ptime from time_t from time.h (whole seconds since UNIX)
Definition: time.h:163
static duration_type subtract(const time_type &t1, const time_type &t2)
Subtract one time from another.
Definition: time.h:261
static time_type now()
Get the current time.
Definition: time.h:255
std::string goby_time_as_string(const boost::posix_time::ptime &t=goby_time())
Simple string representation of goby_time()
Definition: time.h:150
static time_type add(const time_type &t, const duration_type &d)
Add a duration to a time.
Definition: time.h:258
double goby_time< double >()
Returns current UTC time as seconds and fractional seconds since 1970-01-01 00:00:00.
Definition: time.h:130
ReturnType goby_time()
Returns current UTC time as a boost::posix_time::ptime.
Definition: time.h:104
double time_duration2double(boost::posix_time::time_duration time_of_day)
time duration to double number of seconds: good to the microsecond
Definition: time.h:176
std::string goby_file_timestamp()
ISO string representation of goby_time()
Definition: time.h:156
uint64 ptime2unix_microsec(boost::posix_time::ptime given_time)
convert from boost date_time ptime to the number of microseconds since 1/1/1970 0:00 UTC ("UNIX Time"...
Definition: time.cpp:71
std::time_t ptime2time_t(boost::posix_time::ptime t)
convert from ptime to time_t from time.h (whole seconds since UNIX)
Definition: time.h:169
The global namespace for the Goby project.
static bool less_than(const time_type &t1, const time_type &t2)
Test whether one time is less than another.
Definition: time.h:264
boost::posix_time::ptime unix_microsec2ptime(uint64 given_time)
convert to boost date_time ptime from the number of microseconds since 1/1/1970 0:00 UTC ("UNIX Time"...
Definition: time.cpp:93
boost::posix_time::time_duration duration_type
The duration type.
Definition: time.h:252
double ptime2unix_double(boost::posix_time::ptime given_time)
convert from boost date_time ptime to the number of seconds (including fractional) since 1/1/1970 0:0...
Definition: time.cpp:28
google::protobuf::uint64 uint64
an unsigned 64 bit integer
boost::posix_time::ptime unix_double2ptime(double given_time)
convert to boost date_time ptime from the number of seconds (including fractional) since 1/1/1970 0:0...
Definition: time.cpp:47
static boost::posix_time::time_duration to_posix_duration(const duration_type &d)
Convert to POSIX duration type.
Definition: time.h:267
boost::posix_time::ptime time_type
The time type.
Definition: time.h:249