time.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/common/time.h"
00018 
00019 #include <time.h>
00020 
00021 #include <cerrno>
00022 #include <cstring>
00023 #include <string>
00024 
00025 #include "glog/logging.h"
00026 
00027 namespace cartographer {
00028 namespace common {
00029 
00030 Duration FromSeconds(const double seconds) {
00031   return std::chrono::duration_cast<Duration>(
00032       std::chrono::duration<double>(seconds));
00033 }
00034 
00035 double ToSeconds(const Duration duration) {
00036   return std::chrono::duration_cast<std::chrono::duration<double>>(duration)
00037       .count();
00038 }
00039 
00040 double ToSeconds(const std::chrono::steady_clock::duration duration) {
00041   return std::chrono::duration_cast<std::chrono::duration<double>>(duration)
00042       .count();
00043 }
00044 
00045 Time FromUniversal(const int64 ticks) { return Time(Duration(ticks)); }
00046 
00047 int64 ToUniversal(const Time time) { return time.time_since_epoch().count(); }
00048 
00049 std::ostream& operator<<(std::ostream& os, const Time time) {
00050   os << std::to_string(ToUniversal(time));
00051   return os;
00052 }
00053 
00054 common::Duration FromMilliseconds(const int64 milliseconds) {
00055   return std::chrono::duration_cast<Duration>(
00056       std::chrono::milliseconds(milliseconds));
00057 }
00058 
00059 double GetThreadCpuTimeSeconds() {
00060 #ifndef WIN32
00061   struct timespec thread_cpu_time;
00062   CHECK(clock_gettime(CLOCK_THREAD_CPUTIME_ID, &thread_cpu_time) == 0)
00063       << std::strerror(errno);
00064   return thread_cpu_time.tv_sec + 1e-9 * thread_cpu_time.tv_nsec;
00065 #else
00066   return 0.;
00067 #endif
00068 }
00069 
00070 }  // namespace common
00071 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:36