time_conversion.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
20 #include "ros/ros.h"
21 
22 namespace cartographer_ros {
23 
25  int64_t uts_timestamp = ::cartographer::common::ToUniversal(time);
26  int64_t ns_since_unix_epoch =
27  (uts_timestamp -
28  ::cartographer::common::kUtsEpochOffsetFromUnixEpochInSeconds *
29  10000000ll) *
30  100ll;
31  ::ros::Time ros_time;
32  ros_time.fromNSec(ns_since_unix_epoch);
33  return ros_time;
34 }
35 
36 // TODO(pedrofernandez): Write test.
37 ::cartographer::common::Time FromRos(const ::ros::Time& time) {
38  // The epoch of the ICU Universal Time Scale is "0001-01-01 00:00:00.0 +0000",
39  // exactly 719162 days before the Unix epoch.
40  return ::cartographer::common::FromUniversal(
41  (time.sec +
43  10000000ll +
44  (time.nsec + 50) / 100); // + 50 to get the rounding correct.
45 }
46 
47 } // namespace cartographer_ros
Time & fromNSec(uint64_t t)
constexpr int64 kUtsEpochOffsetFromUnixEpochInSeconds
UniversalTimeScaleClock::time_point Time
::cartographer::common::Time FromRos(const ::ros::Time &time)
::ros::Time ToRos(::cartographer::common::Time time)


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05