moveit2
The MoveIt Motion Planning Framework for ROS 2.
generated_time.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2022, Metro Robots
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 Metro Robots 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 /* Author: David V. Lu!! */
36 
37 #pragma once
38 
39 #include <filesystem>
40 #include <string>
41 
42 namespace moveit_setup
43 {
49 using GeneratedTime = std::filesystem::file_time_type;
50 
54 template <typename CLOCK>
55 inline GeneratedTime convertTime(const typename CLOCK::time_point& t0)
56 {
57  return std::chrono::time_point_cast<GeneratedTime::duration>(t0 - CLOCK::now() + GeneratedTime::clock::now());
58 }
59 
63 template <typename CLOCK>
64 inline typename CLOCK::time_point convertTime(const GeneratedTime& t0)
65 {
66  return std::chrono::time_point_cast<typename CLOCK::duration>(t0 - GeneratedTime::clock::now() + CLOCK::now());
67 }
68 
72 template <typename CLOCK>
73 inline GeneratedTime convertTime(long int epoch)
74 {
75  auto t0 = CLOCK::from_time_t(epoch);
76  return convertTime<CLOCK>(t0);
77 }
78 
82 inline GeneratedTime fromEpoch(long int epoch)
83 {
84  return convertTime<std::chrono::system_clock>(epoch);
85 }
86 
90 template <typename CLOCK>
91 inline std::time_t toStandardTime(const GeneratedTime& t)
92 {
93  return CLOCK::to_time_t(convertTime<CLOCK>(t));
94 }
95 
99 inline long int toEpoch(const GeneratedTime& t)
100 {
101  return toStandardTime<std::chrono::system_clock>(t);
102 }
103 
107 inline std::string toString(const GeneratedTime& t)
108 {
109  std::time_t tt = toStandardTime<std::chrono::system_clock>(t);
110  char buff[20];
111  strftime(buff, 20, "%Y-%m-%d %H:%M:%S", localtime(&tt));
112  return std::string(buff);
113 }
114 
115 } // namespace moveit_setup
long int toEpoch(const GeneratedTime &t)
Convert a GeneratedTime to an integral epoch (using system_clock)
std::time_t toStandardTime(const GeneratedTime &t)
Convert a GeneratedTime to a std::time_t (using system_clock)
GeneratedTime fromEpoch(long int epoch)
Convert an integral epoch to GeneratedTime (using system_clock)
std::filesystem::file_time_type GeneratedTime
GeneratedTime convertTime(const typename CLOCK::time_point &t0)
Convert a time_point from an arbitrary clock to GeneratedTime.
std::string toString(const GeneratedTime &t)
Convert a GeneratedTime to a std::string (using system_clock)