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.
include
tf2
time.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2015-2016, Open Source Robotics Foundation, Inc.
3
* All rights reserved.
4
*
5
* Redistribution and use in source and binary forms, with or without
6
* modification, are permitted provided that the following conditions are met:
7
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of the Willow Garage, Inc. 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 OWNER 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
30
#ifndef TF2_TIME_H
31
#define TF2_TIME_H
32
33
#include <chrono>
34
#include <cmath>
35
#include <stdio.h>
36
#include <string>
37
#include <thread>
38
#include <iostream>
39
40
#include <
tf2/visibility_control.h
>
41
42
namespace
tf2
43
{
44
using
Duration
=
std::chrono::nanoseconds
;
45
using
TimePoint
=
std::chrono::time_point<std::chrono::system_clock, Duration>
;
46
47
48
using
IDuration
=
std::chrono::duration<int, std::nano>
;
49
// This is the zero time in ROS
50
static
const
TimePoint
TimePointZero =
TimePoint
(
IDuration::zero
());
51
52
inline
TimePoint
get_now
()
53
{
54
return
std::chrono::system_clock::now
();
55
}
56
57
inline
Duration
durationFromSec
(
double
t_sec)
58
{
59
int32_t sec, nsec;
60
sec =
static_cast<
int32_t
>
(floor(t_sec));
61
nsec =
static_cast<
int32_t
>
(
std::round
((t_sec - sec) * 1e9));
62
// avoid rounding errors
63
sec += (nsec / 1000000000l);
64
nsec %= 1000000000l;
65
return
std::chrono::seconds
(sec) +
std::chrono::nanoseconds
(nsec);
66
}
67
68
inline
TimePoint
timeFromSec
(
double
t_sec)
69
{
70
return
tf2::TimePoint
(
durationFromSec
(t_sec));
71
}
72
73
inline
double
durationToSec
(
const
tf2::Duration
& input){
74
int64_t count = input.
count
();
75
76
// scale the nanoseconds separately for improved accuracy
77
int32_t sec, nsec;
78
nsec =
static_cast<
int32_t
>
(count % 1000000000l);
79
sec =
static_cast<
int32_t
>
((count - nsec) / 1000000000l);
80
81
double
sec_double, nsec_double;
82
nsec_double = 1e-9 *
static_cast<
double
>
(nsec);
83
sec_double =
static_cast<
double
>
(sec);
84
return
sec_double + nsec_double;
85
}
86
87
inline
double
timeToSec
(
const
TimePoint
& timepoint)
88
{
89
return
durationToSec
(
Duration
(timepoint.
time_since_epoch
()));
90
}
91
92
TF2_PUBLIC
93
std::string
displayTimePoint
(
const
TimePoint
& stamp);
94
95
}
96
97
#endif // TF2_TIME_H
tf2::timeFromSec
TimePoint timeFromSec(double t_sec)
Definition:
time.h:68
std::string
tf2::get_now
TimePoint get_now()
Definition:
time.h:52
tf2::Duration
std::chrono::nanoseconds Duration
Definition:
time.h:44
tf2::displayTimePoint
std::string displayTimePoint(const TimePoint &stamp)
std::chrono::nanoseconds
tf2::durationFromSec
Duration durationFromSec(double t_sec)
Definition:
time.h:57
std::chrono::duration::zero
T zero(T... args)
tf2::durationToSec
double durationToSec(const tf2::Duration &input)
Definition:
time.h:73
std::chrono::time_point::time_since_epoch
T time_since_epoch(T... args)
tf2::timeToSec
double timeToSec(const TimePoint &timepoint)
Definition:
time.h:87
tf2::TimePoint
std::chrono::time_point< std::chrono::system_clock, Duration > TimePoint
Definition:
time.h:45
std::chrono::time_point< std::chrono::system_clock, Duration >
visibility_control.h
std::round
T round(T... args)
tf2
Definition:
buffer_core.h:55
std::chrono::nanoseconds::count
T count(T... args)
TF2_PUBLIC
#define TF2_PUBLIC
Definition:
visibility_control.h:58
std::chrono::system_clock::now
T now(T... args)
Generated by
1.8.17