00001 // Copyright (C) 2019 Matthew Pitropov, Joshua Whitley 00002 // All rights reserved. 00003 // 00004 // Software License Agreement (BSD License 2.0) 00005 // 00006 // Redistribution and use in source and binary forms, with or without 00007 // modification, are permitted provided that the following conditions 00008 // are met: 00009 // 00010 // * Redistributions of source code must retain the above copyright 00011 // notice, this list of conditions and the following disclaimer. 00012 // * Redistributions in binary form must reproduce the above 00013 // copyright notice, this list of conditions and the following 00014 // disclaimer in the documentation and/or other materials provided 00015 // with the distribution. 00016 // * Neither the name of {copyright_holder} nor the names of its 00017 // contributors may be used to endorse or promote products derived 00018 // from this software without specific prior written permission. 00019 // 00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 // POSSIBILITY OF SUCH DAMAGE. 00032 00033 #include "velodyne_driver/time_conversion.hpp" 00034 #include <ros/time.h> 00035 #include <gtest/gtest.h> 00036 00037 TEST(TimeConversion, BytesToTimestamp) 00038 { 00039 ros::Time::init(); 00040 ros::Time ros_stamp = ros::Time::now(); 00041 00042 // get the seconds past the hour and multiply by 1million to convert to microseconds 00043 // divide nanoseconds by 1000 to convert to microseconds 00044 uint32_t since_the_hour = ((ros_stamp.sec % 3600) * 1000000) + ros_stamp.nsec / 1000; 00045 00046 uint8_t native_format[4]; 00047 native_format[0] = 0xFF & since_the_hour; 00048 native_format[1] = 0xFF & (((uint32_t)since_the_hour) >> 8); 00049 native_format[2] = 0xFF & (((uint32_t)since_the_hour) >> 16); 00050 native_format[3] = 0xFF & (((uint32_t)since_the_hour) >> 24); 00051 00052 ros::Time ros_stamp_converted = rosTimeFromGpsTimestamp(native_format); 00053 00054 ASSERT_EQ(ros_stamp_converted.sec, ros_stamp.sec); 00055 ASSERT_NEAR(ros_stamp_converted.nsec, ros_stamp.nsec, 1000); 00056 } 00057 00058 int main(int argc, char **argv) 00059 { 00060 ::testing::InitGoogleTest(&argc, argv); 00061 int ret = RUN_ALL_TESTS(); 00062 return ret; 00063 }