tf2  master
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
time.h
Go to the documentation of this file.
1 // Copyright 2015-2016, Open Source Robotics Foundation, Inc. All rights reserved.
2 //
3 // Redistribution and use in source and binary forms, with or without
4 // modification, are permitted provided that the following conditions are met:
5 //
6 // * Redistributions of source code must retain the above copyright
7 // notice, this list of conditions and the following disclaimer.
8 //
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 //
13 // * Neither the name of the Open Source Robotics Foundation nor the names of its
14 // contributors may be used to endorse or promote products derived from
15 // this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 
29 #ifndef TF2__TIME_H_
30 #define TF2__TIME_H_
31 
32 #include <chrono>
33 #include <cmath>
34 #include <string>
35 
36 #include "tf2/visibility_control.h"
37 
38 namespace tf2
39 {
42 
44 // This is the zero time in ROS
45 static const TimePoint TimePointZero = TimePoint(IDuration::zero());
46 
48 {
50 }
51 
52 inline Duration durationFromSec(double t_sec)
53 {
54  int32_t sec, nsec;
55  sec = static_cast<int32_t>(floor(t_sec));
56  nsec = static_cast<int32_t>(std::round((t_sec - sec) * 1e9));
57  // avoid rounding errors
58  sec += (nsec / 1000000000l);
59  nsec %= 1000000000l;
61 }
62 
63 inline TimePoint timeFromSec(double t_sec)
64 {
65  return tf2::TimePoint(durationFromSec(t_sec));
66 }
67 
68 inline double durationToSec(const tf2::Duration & input)
69 {
70  int64_t count = input.count();
71 
72  // scale the nanoseconds separately for improved accuracy
73  int32_t sec, nsec;
74  nsec = static_cast<int32_t>(count % 1000000000l);
75  sec = static_cast<int32_t>((count - nsec) / 1000000000l);
76 
77  double sec_double, nsec_double;
78  nsec_double = 1e-9 * static_cast<double>(nsec);
79  sec_double = static_cast<double>(sec);
80  return sec_double + nsec_double;
81 }
82 
83 inline double timeToSec(const TimePoint & timepoint)
84 {
85  return durationToSec(Duration(timepoint.time_since_epoch()));
86 }
87 
90 
91 } // namespace tf2
92 
93 #endif // TF2__TIME_H_
tf2::timeFromSec
TimePoint timeFromSec(double t_sec)
Definition: time.h:63
std::string
tf2::get_now
TimePoint get_now()
Definition: time.h:47
tf2::Duration
std::chrono::nanoseconds Duration
Definition: time.h:40
tf2::displayTimePoint
std::string displayTimePoint(const TimePoint &stamp)
std::chrono::nanoseconds
tf2::durationFromSec
Duration durationFromSec(double t_sec)
Definition: time.h:52
std::chrono::duration::zero
T zero(T... args)
tf2::durationToSec
double durationToSec(const tf2::Duration &input)
Definition: time.h:68
std::chrono::time_point::time_since_epoch
T time_since_epoch(T... args)
tf2::timeToSec
double timeToSec(const TimePoint &timepoint)
Definition: time.h:83
tf2::TimePoint
std::chrono::time_point< std::chrono::system_clock, Duration > TimePoint
Definition: time.h:41
std::chrono::time_point< std::chrono::system_clock, Duration >
visibility_control.h
std::round
T round(T... args)
tf2
Definition: buffer_core.h:53
std::chrono::nanoseconds::count
T count(T... args)
TF2_PUBLIC
#define TF2_PUBLIC
Definition: visibility_control.h:57
std::chrono::system_clock::now
T now(T... args)