timeconversiontest.cpp
Go to the documentation of this file.
1 // Copyright (C) 2019 Matthew Pitropov, Joshua Whitley
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of {copyright_holder} nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
34 #include <ros/time.h>
35 #include <gtest/gtest.h>
36 
37 TEST(TimeConversion, BytesToTimestamp)
38 {
40  ros::Time ros_stamp = ros::Time::now();
41 
42  // get the seconds past the hour and multiply by 1million to convert to microseconds
43  // divide nanoseconds by 1000 to convert to microseconds
44  uint32_t since_the_hour = ((ros_stamp.sec % 3600) * 1000000) + ros_stamp.nsec / 1000;
45 
46  uint8_t native_format[4];
47  native_format[0] = 0xFF & since_the_hour;
48  native_format[1] = 0xFF & (((uint32_t)since_the_hour) >> 8);
49  native_format[2] = 0xFF & (((uint32_t)since_the_hour) >> 16);
50  native_format[3] = 0xFF & (((uint32_t)since_the_hour) >> 24);
51 
52  ros::Time ros_stamp_converted = rosTimeFromGpsTimestamp(native_format);
53 
54  ASSERT_EQ(ros_stamp_converted.sec, ros_stamp.sec);
55  ASSERT_NEAR(ros_stamp_converted.nsec, ros_stamp.nsec, 1000);
56 }
57 
58 int main(int argc, char **argv)
59 {
60  ::testing::InitGoogleTest(&argc, argv);
61  int ret = RUN_ALL_TESTS();
62  return ret;
63 }
TEST(TimeConversion, BytesToTimestamp)
static void init()
static Time now()
ros::Time rosTimeFromGpsTimestamp(const uint8_t *const data)
int main(int argc, char **argv)


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Sun Sep 6 2020 03:25:28