time_conversion.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_ros/time_conversion.h"
00018 
00019 #include "cartographer/common/time.h"
00020 #include "ros/ros.h"
00021 
00022 namespace cartographer_ros {
00023 
00024 ::ros::Time ToRos(::cartographer::common::Time time) {
00025   int64_t uts_timestamp = ::cartographer::common::ToUniversal(time);
00026   int64_t ns_since_unix_epoch =
00027       (uts_timestamp -
00028        ::cartographer::common::kUtsEpochOffsetFromUnixEpochInSeconds *
00029            10000000ll) *
00030       100ll;
00031   ::ros::Time ros_time;
00032   ros_time.fromNSec(ns_since_unix_epoch);
00033   return ros_time;
00034 }
00035 
00036 // TODO(pedrofernandez): Write test.
00037 ::cartographer::common::Time FromRos(const ::ros::Time& time) {
00038   // The epoch of the ICU Universal Time Scale is "0001-01-01 00:00:00.0 +0000",
00039   // exactly 719162 days before the Unix epoch.
00040   return ::cartographer::common::FromUniversal(
00041       (time.sec +
00042        ::cartographer::common::kUtsEpochOffsetFromUnixEpochInSeconds) *
00043           10000000ll +
00044       (time.nsec + 50) / 100);  // + 50 to get the rounding correct.
00045 }
00046 
00047 }  // namespace cartographer_ros


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28