time.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef ROS_TIME_H_INCLUDED
36 #define ROS_TIME_H_INCLUDED
37 
38 /*********************************************************************
39  ** Pragmas
40  *********************************************************************/
41 
42 #ifdef _MSC_VER
43  // Rostime has some magic interface that doesn't directly include
44  // its implementation, this just disables those warnings.
45  #pragma warning(disable: 4244)
46  #pragma warning(disable: 4661)
47 #endif
48 
49 /*********************************************************************
50  ** Headers
51  *********************************************************************/
52 
53 #include <ros/platform.h>
54 #include <iostream>
55 #include <cmath>
56 #include <ros/exception.h>
57 #include "duration.h"
58 #include <boost/math/special_functions/round.hpp>
59 #include "rostime_decl.h"
60 
61 /*********************************************************************
62  ** Cross Platform Headers
63  *********************************************************************/
64 
65 #ifdef WIN32
66  #include <sys/timeb.h>
67 #else
68  #include <sys/time.h>
69 #endif
70 
71 namespace boost {
72  namespace posix_time {
73  class ptime;
74  class time_duration;
75  }
76 }
77 
78 namespace ros
79 {
80 
81  /*********************************************************************
82  ** Exceptions
83  *********************************************************************/
84 
89  {
90  public:
92  : Exception("Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called. "
93  "If this is a standalone app or test that just uses ros::Time and does not communicate over ROS, you may also call ros::Time::init()")
94  {}
95  };
96 
103  {
104  public:
106  : Exception("This windows platform does not "
107  "support the high-performance timing api.")
108  {}
109  };
110 
111  /*********************************************************************
112  ** Functions
113  *********************************************************************/
114 
115  ROSTIME_DECL void normalizeSecNSec(uint64_t& sec, uint64_t& nsec);
116  ROSTIME_DECL void normalizeSecNSec(uint32_t& sec, uint32_t& nsec);
117  ROSTIME_DECL void normalizeSecNSecUnsigned(int64_t& sec, int64_t& nsec);
118  ROSTIME_DECL void ros_walltime(uint32_t& sec, uint32_t& nsec);
119  ROSTIME_DECL void ros_steadytime(uint32_t& sec, uint32_t& nsec);
120 
121  /*********************************************************************
122  ** Time Classes
123  *********************************************************************/
124 
129  template<class T, class D>
130  class TimeBase
131  {
132  public:
133  uint32_t sec, nsec;
134 
135  TimeBase() : sec(0), nsec(0) { }
136  TimeBase(uint32_t _sec, uint32_t _nsec) : sec(_sec), nsec(_nsec)
137  {
138  normalizeSecNSec(sec, nsec);
139  }
140  explicit TimeBase(double t) { fromSec(t); }
141  D operator-(const T &rhs) const;
142  T operator+(const D &rhs) const;
143  T operator-(const D &rhs) const;
144  T& operator+=(const D &rhs);
145  T& operator-=(const D &rhs);
146  bool operator==(const T &rhs) const;
147  inline bool operator!=(const T &rhs) const { return !(*static_cast<const T*>(this) == rhs); }
148  bool operator>(const T &rhs) const;
149  bool operator<(const T &rhs) const;
150  bool operator>=(const T &rhs) const;
151  bool operator<=(const T &rhs) const;
152 
153  double toSec() const { return static_cast<double>(sec) + 1e-9*static_cast<double>(nsec); };
154  T& fromSec(double t);
155 
156  uint64_t toNSec() const {return static_cast<uint64_t>(sec)*1000000000ull + static_cast<uint64_t>(nsec); }
157  T& fromNSec(uint64_t t);
158 
159  inline bool isZero() const { return sec == 0 && nsec == 0; }
160  inline bool is_zero() const { return isZero(); }
161  boost::posix_time::ptime toBoost() const;
162 
163  };
164 
170  class ROSTIME_DECL Time : public TimeBase<Time, Duration>
171  {
172  public:
174  : TimeBase<Time, Duration>()
175  {}
176 
177  Time(uint32_t _sec, uint32_t _nsec)
178  : TimeBase<Time, Duration>(_sec, _nsec)
179  {}
180 
181  explicit Time(double t) { fromSec(t); }
182 
187  static Time now();
192  static bool sleepUntil(const Time& end);
193 
194  static void init();
195  static void shutdown();
196  static void setNow(const Time& new_now);
197  static bool useSystemTime();
198  static bool isSimTime();
199  static bool isSystemTime();
200 
204  static bool isValid();
208  static bool waitForValid();
212  static bool waitForValid(const ros::WallDuration& timeout);
213 
214  static Time fromBoost(const boost::posix_time::ptime& t);
215  static Time fromBoost(const boost::posix_time::time_duration& d);
216  };
217 
218  extern ROSTIME_DECL const Time TIME_MAX;
219  extern ROSTIME_DECL const Time TIME_MIN;
220 
226  class ROSTIME_DECL WallTime : public TimeBase<WallTime, WallDuration>
227  {
228  public:
231  {}
232 
233  WallTime(uint32_t _sec, uint32_t _nsec)
234  : TimeBase<WallTime, WallDuration>(_sec, _nsec)
235  {}
236 
237  explicit WallTime(double t) { fromSec(t); }
238 
242  static WallTime now();
243 
248  static bool sleepUntil(const WallTime& end);
249 
250  static bool isSystemTime() { return true; }
251  };
252 
260  class ROSTIME_DECL SteadyTime : public TimeBase<SteadyTime, WallDuration>
261  {
262  public:
265  {}
266 
267  SteadyTime(uint32_t _sec, uint32_t _nsec)
268  : TimeBase<SteadyTime, WallDuration>(_sec, _nsec)
269  {}
270 
271  explicit SteadyTime(double t) { fromSec(t); }
272 
276  static SteadyTime now();
277 
282  static bool sleepUntil(const SteadyTime& end);
283 
284  static bool isSystemTime() { return true; }
285  };
286 
287  ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const Time &rhs);
288  ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const WallTime &rhs);
289  ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const SteadyTime &rhs);
290 }
291 
292 #endif // ROS_TIME_H
293 
ROSTIME_DECL std::ostream & operator<<(std::ostream &os, const SteadyTime &rhs)
Definition: src/time.cpp:494
Definition: duration.h:56
TimeBase()
Definition: time.h:135
static bool isSystemTime()
Definition: time.h:284
ROSTIME_DECL void ros_steadytime(uint32_t &sec, uint32_t &nsec)
Definition: src/time.cpp:183
Time representation. May either represent wall clock time or ROS clock time.
Definition: time.h:170
uint32_t sec
Definition: time.h:133
bool is_zero() const
Definition: time.h:160
WallTime(uint32_t _sec, uint32_t _nsec)
Definition: time.h:233
ROSTIME_DECL void normalizeSecNSecUnsigned(int64_t &sec, int64_t &nsec)
Definition: src/time.cpp:559
bool operator!=(const T &rhs) const
Definition: time.h:147
SteadyTime(uint32_t _sec, uint32_t _nsec)
Definition: time.h:267
Time(double t)
Definition: time.h:181
TimeBase(uint32_t _sec, uint32_t _nsec)
Definition: time.h:136
WallTime(double t)
Definition: time.h:237
Duration representation for use with the WallTime class.
Definition: duration.h:136
Thrown if the ros subsystem hasn&#39;t been initialised before use.
Definition: time.h:88
ROSTIME_DECL void ros_walltime(uint32_t &sec, uint32_t &nsec)
Definition: src/time.cpp:104
Time(uint32_t _sec, uint32_t _nsec)
Definition: time.h:177
Base class for Time implementations. Provides storage, common functions and operator overloads...
Definition: time.h:130
Thrown if windows high perf. timestamping is unavailable.
Definition: time.h:102
SteadyTime(double t)
Definition: time.h:271
Time representation. Always wall-clock time.
Definition: time.h:226
TimeBase(double t)
Definition: time.h:140
Time()
Definition: time.h:173
ROSTIME_DECL void normalizeSecNSec(uint32_t &sec, uint32_t &nsec)
Definition: src/time.cpp:548
uint64_t toNSec() const
Definition: time.h:156
ROSTIME_DECL const Time TIME_MAX
Time representation. Always steady-clock time.
Definition: time.h:260
static bool isSystemTime()
Definition: time.h:250
ROSTIME_DECL const Time TIME_MIN
Duration representation for use with the Time class.
Definition: duration.h:108
WallTime()
Definition: time.h:229
double toSec() const
Definition: time.h:153
bool isZero() const
Definition: time.h:159
#define ROSTIME_DECL
Definition: rostime_decl.h:52


rostime
Author(s): Josh Faust
autogenerated on Sat Apr 6 2019 02:52:21