time_conversion_test.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 
19 #include <chrono>
20 
22 #include "gtest/gtest.h"
23 #include "ros/ros.h"
24 
25 namespace cartographer_ros {
26 namespace {
27 
28 TEST(TimeConversion, testToRos) {
29  std::vector<int64> values = {0, 1469091375, 1466481821, 1462101382,
30  1468238899};
31  for (int64 seconds_since_epoch : values) {
32  ::ros::Time ros_now;
33  ros_now.fromSec(seconds_since_epoch);
34  ::cartographer::common::Time cartographer_now(
36  seconds_since_epoch +
38  EXPECT_EQ(cartographer_now, ::cartographer_ros::FromRos(ros_now));
39  EXPECT_EQ(ros_now, ::cartographer_ros::ToRos(cartographer_now));
40  }
41 }
42 
43 } // namespace
44 } // namespace cartographer_ros
std::vector< double > values
constexpr int64 kUtsEpochOffsetFromUnixEpochInSeconds
UniversalTimeScaleClock::time_point Time
Time & fromSec(double t)
Duration FromSeconds(const double seconds)
TEST(ActionClientDestruction, persistent_goal_handles_1)
::cartographer::common::Time FromRos(const ::ros::Time &time)
int64_t int64
::ros::Time ToRos(::cartographer::common::Time time)


cartographer_ros
Author(s):
autogenerated on Wed Jun 5 2019 22:35:56