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 #ifndef VELODYNE_DRIVER_TIME_CONVERSION_HPP 00034 #define VELODYNE_DRIVER_TIME_CONVERSION_HPP 00035 00036 #include <ros/ros.h> 00037 #include <ros/time.h> 00038 00049 ros::Time resolveHourAmbiguity(const ros::Time &stamp, const ros::Time &nominal_stamp) { 00050 const int HALFHOUR_TO_SEC = 1800; 00051 ros::Time retval = stamp; 00052 if (nominal_stamp.sec > stamp.sec) { 00053 if (nominal_stamp.sec - stamp.sec > HALFHOUR_TO_SEC) { 00054 retval.sec = retval.sec + 2*HALFHOUR_TO_SEC; 00055 } 00056 } else if (stamp.sec - nominal_stamp.sec > HALFHOUR_TO_SEC) { 00057 retval.sec = retval.sec - 2*HALFHOUR_TO_SEC; 00058 } 00059 return retval; 00060 } 00061 00062 ros::Time rosTimeFromGpsTimestamp(const uint8_t * const data) { 00063 const int HOUR_TO_SEC = 3600; 00064 // time for each packet is a 4 byte uint 00065 // It is the number of microseconds from the top of the hour 00066 uint32_t usecs = (uint32_t) ( ((uint32_t) data[3]) << 24 | 00067 ((uint32_t) data[2] ) << 16 | 00068 ((uint32_t) data[1] ) << 8 | 00069 ((uint32_t) data[0] )); 00070 ros::Time time_nom = ros::Time::now(); // use this to recover the hour 00071 uint32_t cur_hour = time_nom.sec / HOUR_TO_SEC; 00072 ros::Time stamp = ros::Time((cur_hour * HOUR_TO_SEC) + (usecs / 1000000), 00073 (usecs % 1000000) * 1000); 00074 stamp = resolveHourAmbiguity(stamp, time_nom); 00075 return stamp; 00076 } 00077 00078 #endif //VELODYNE_DRIVER_TIME_CONVERSION_HPP