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 #if defined(_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  {
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  static const T MIN;
164  static const T MAX;
165  static const T ZERO;
166  static const T UNINITIALIZED;
167  };
168 
174  class ROSTIME_DECL Time : public TimeBase<Time, Duration>
175  {
176  public:
178  : TimeBase<Time, Duration>()
179  {}
180 
181  Time(uint32_t _sec, uint32_t _nsec)
182  : TimeBase<Time, Duration>(_sec, _nsec)
183  {}
184 
185  explicit Time(double t) { fromSec(t); }
186 
191  static Time now();
196  static bool sleepUntil(const Time& end);
197 
198  static void init();
199  static void shutdown();
200  static void setNow(const Time& new_now);
201  static bool useSystemTime();
202  static bool isSimTime();
203  static bool isSystemTime();
204 
208  static bool isValid();
212  static bool waitForValid();
216  static bool waitForValid(const ros::WallDuration& timeout);
217 
218  static Time fromBoost(const boost::posix_time::ptime& t);
219  static Time fromBoost(const boost::posix_time::time_duration& d);
220  };
221 
222  extern ROSTIME_DECL const Time TIME_MAX;
223  extern ROSTIME_DECL const Time TIME_MIN;
228 
234  class ROSTIME_DECL WallTime : public TimeBase<WallTime, WallDuration>
235  {
236  public:
239  {}
240 
241  WallTime(uint32_t _sec, uint32_t _nsec)
242  : TimeBase<WallTime, WallDuration>(_sec, _nsec)
243  {}
244 
245  explicit WallTime(double t) { fromSec(t); }
246 
250  static WallTime now();
251 
256  static bool sleepUntil(const WallTime& end);
257 
258  static bool isSystemTime() { return true; }
259  };
260 
265 
273  class ROSTIME_DECL SteadyTime : public TimeBase<SteadyTime, WallDuration>
274  {
275  public:
278  {}
279 
280  SteadyTime(uint32_t _sec, uint32_t _nsec)
281  : TimeBase<SteadyTime, WallDuration>(_sec, _nsec)
282  {}
283 
284  explicit SteadyTime(double t) { fromSec(t); }
285 
289  static SteadyTime now();
290 
295  static bool sleepUntil(const SteadyTime& end);
296 
297  static bool isSystemTime() { return true; }
298  };
299 
304 
305  ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const Time &rhs);
306  ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const WallTime &rhs);
307  ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const SteadyTime &rhs);
308 }
309 
310 #endif // ROS_TIME_H
ros::ros_steadytime
ROSTIME_DECL void ros_steadytime(uint32_t &sec, uint32_t &nsec)
Definition: src/time.cpp:172
ros::ros_walltime
ROSTIME_DECL void ros_walltime(uint32_t &sec, uint32_t &nsec)
Definition: src/time.cpp:143
ros::normalizeSecNSecUnsigned
ROSTIME_DECL void normalizeSecNSecUnsigned(int64_t &sec, int64_t &nsec)
Definition: src/time.cpp:537
ros::TimeBase::operator<
bool operator<(const T &rhs) const
Definition: impl/time.h:180
ros::operator<<
ROSTIME_DECL std::ostream & operator<<(std::ostream &os, const Duration &rhs)
Definition: src/time.cpp:359
ros::TimeBase::fromSec
T & fromSec(double t)
Definition: impl/time.h:114
ros::TimeBase::operator!=
bool operator!=(const T &rhs) const
Definition: time.h:149
ros::SteadyTime::SteadyTime
SteadyTime(uint32_t _sec, uint32_t _nsec)
Definition: time.h:280
ros
ros::WallTime::WallTime
WallTime()
Definition: time.h:237
ros::TimeBase::toSec
double toSec() const
Definition: time.h:155
ros::NoHighPerformanceTimersException
Thrown if windows high perf. timestamping is unavailable.
Definition: time.h:102
boost
Definition: duration.h:56
ros::Exception
ros::SteadyTime::isSystemTime
static bool isSystemTime()
Definition: time.h:297
ros::TimeBase::MAX
static const T MAX
Maximum representable time.
Definition: time.h:166
ros::Time::Time
Time(uint32_t _sec, uint32_t _nsec)
Definition: time.h:181
ros::Time::Time
Time(double t)
Definition: time.h:185
ros::TimeBase
Base class for Time implementations. Provides storage, common functions and operator overloads....
Definition: time.h:130
ros::TimeBase::isZero
bool isZero() const
Definition: time.h:161
ros::SteadyTime
Time representation. Always steady-clock time.
Definition: time.h:273
ros::TimeBase::ZERO
static const T ZERO
Zero (invalid) time.
Definition: time.h:167
duration.h
ros::SteadyTime::SteadyTime
SteadyTime(double t)
Definition: time.h:284
ros::TimeBase::toBoost
boost::posix_time::ptime toBoost() const
Definition: impl/time.h:221
ros::TimeBase::operator+
T operator+(const D &rhs) const
Definition: impl/time.h:147
ros::TimeBase::operator<=
bool operator<=(const T &rhs) const
Definition: impl/time.h:200
ros::TimeBase::operator-=
T & operator-=(const D &rhs)
Definition: impl/time.h:167
ros::TimeBase::operator>
bool operator>(const T &rhs) const
Definition: impl/time.h:190
ros::WallTime
Time representation. Always wall-clock time.
Definition: time.h:234
ros::TimeBase::sec
uint32_t sec
Definition: time.h:135
ros::TimeBase::nsec
uint32_t nsec
Definition: time.h:135
ros::TIME_MIN
const ROSTIME_DECL Time TIME_MIN
ros::TimeNotInitializedException
Thrown if the ros subsystem hasn't been initialised before use.
Definition: time.h:88
ros::TimeBase::operator>=
bool operator>=(const T &rhs) const
Definition: impl/time.h:210
ros::TimeBase::operator-
D operator-(const T &rhs) const
Definition: impl/time.h:134
ros::WallTime::WallTime
WallTime(double t)
Definition: time.h:245
ros::Time::Time
Time()
Definition: time.h:177
ros::NoHighPerformanceTimersException::NoHighPerformanceTimersException
NoHighPerformanceTimersException()
Definition: time.h:105
ros::TIME_MAX
const ROSTIME_DECL Time TIME_MAX
ros::TimeBase::fromNSec
T & fromNSec(uint64_t t)
Definition: impl/time.h:100
ros::Time
Time representation. May either represent wall clock time or ROS clock time.
Definition: time.h:174
ros::WallTime::isSystemTime
static bool isSystemTime()
Definition: time.h:258
ros::TimeBase::MIN
static const T MIN
Minimum representable time.
Definition: time.h:165
ros::TimeBase::UNINITIALIZED
static const T UNINITIALIZED
Uninitialized time.
Definition: time.h:168
ros::TimeBase::toNSec
uint64_t toNSec() const
Definition: time.h:158
ros::SteadyTime::SteadyTime
SteadyTime()
Definition: time.h:276
platform.h
ros::TimeBase::TimeBase
TimeBase()
Definition: time.h:137
ros::TimeBase::operator+=
T & operator+=(const D &rhs)
Definition: impl/time.h:160
ros::TimeBase::is_zero
bool is_zero() const
Definition: time.h:162
ros::WallDuration
Duration representation for use with the WallTime class.
Definition: duration.h:155
ros::WallTime::WallTime
WallTime(uint32_t _sec, uint32_t _nsec)
Definition: time.h:241
ROSTIME_DECL
#define ROSTIME_DECL
Definition: rostime_decl.h:52
ros::Duration
Duration representation for use with the Time class.
Definition: duration.h:117
ros::normalizeSecNSec
ROSTIME_DECL void normalizeSecNSec(uint64_t &sec, uint64_t &nsec)
Definition: src/time.cpp:514
exception.h
rostime_decl.h
ros::TimeBase::operator==
bool operator==(const T &rhs) const
Definition: impl/time.h:174


rostime
Author(s): Josh Faust, Dirk Thomas
autogenerated on Sat Jun 17 2023 02:32:37