Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
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
00037 ::cartographer::common::Time FromRos(const ::ros::Time& time) {
00038
00039
00040 return ::cartographer::common::FromUniversal(
00041 (time.sec +
00042 ::cartographer::common::kUtsEpochOffsetFromUnixEpochInSeconds) *
00043 10000000ll +
00044 (time.nsec + 50) / 100);
00045 }
00046
00047 }