time.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #include <novatel_gps_driver/parsers/time.h>
00031 #include <boost/make_shared.hpp>
00032 
00033 const std::string novatel_gps_driver::TimeParser::MESSAGE_NAME = "TIME";
00034 
00035 uint32_t novatel_gps_driver::TimeParser::GetMessageId() const
00036 {
00037   return MESSAGE_ID;
00038 }
00039 
00040 const std::string novatel_gps_driver::TimeParser::GetMessageName() const
00041 {
00042   return MESSAGE_NAME;
00043 }
00044 
00045 novatel_gps_msgs::TimePtr novatel_gps_driver::TimeParser::ParseBinary(const novatel_gps_driver::BinaryMessage& msg) throw(ParseException)
00046 {
00047   if (msg.data_.size() != BINARY_LENGTH)
00048   {
00049     std::stringstream error;
00050     error << "Unexpected time message size: " << msg.data_.size();
00051     throw ParseException(error.str());
00052   }
00053 
00054   novatel_gps_msgs::TimePtr ros_msg = boost::make_shared<novatel_gps_msgs::Time>();
00055 
00056   uint32_t clock_status = ParseUInt32(&msg.data_[0]);
00057   switch (clock_status)
00058   {
00059     case 0:
00060       ros_msg->clock_status = "VALID";
00061       break;
00062     case 1:
00063       ros_msg->clock_status = "CONVERGING";
00064       break;
00065     case 2:
00066       ros_msg->clock_status = "ITERATING";
00067       break;
00068     case 3:
00069       ros_msg->clock_status = "INVALID";
00070       break;
00071     default:
00072     {
00073       std::stringstream error;
00074       error << "Unexpected clock status: " << clock_status;
00075       throw ParseException(error.str());
00076     }
00077   }
00078   ros_msg->offset = ParseDouble(&msg.data_[4]);
00079   ros_msg->offset_std = ParseDouble(&msg.data_[12]);
00080   ros_msg->utc_offset = ParseDouble(&msg.data_[20]);
00081   ros_msg->utc_year = ParseUInt32(&msg.data_[28]);
00082   ros_msg->utc_month = msg.data_[32];
00083   ros_msg->utc_day = msg.data_[33];
00084   ros_msg->utc_hour = msg.data_[34];
00085   ros_msg->utc_minute = msg.data_[35];
00086   ros_msg->utc_millisecond = ParseUInt32(&msg.data_[36]);
00087   uint32_t utc_status = ParseUInt32(&msg.data_[40]);
00088   switch (utc_status)
00089   {
00090     case 0:
00091       ros_msg->utc_status = "Invalid";
00092       break;
00093     case 1:
00094       ros_msg->utc_status = "Valid";
00095       break;
00096     case 2:
00097       ros_msg->utc_status = "Warning";
00098       break;
00099     default:
00100     {
00101       std::stringstream error;
00102       error << "Unexpected UTC status: " << utc_status;
00103       throw ParseException(error.str());
00104     }
00105   }
00106 
00107   return ros_msg;
00108 }
00109 
00110 novatel_gps_msgs::TimePtr
00111 novatel_gps_driver::TimeParser::ParseAscii(const novatel_gps_driver::NovatelSentence& sentence) throw(ParseException)
00112 {
00113   novatel_gps_msgs::TimePtr msg = boost::make_shared<novatel_gps_msgs::Time>();
00114   if (sentence.body.size() != ASCII_FIELD)
00115   {
00116     std::stringstream error;
00117     error << "Unexpected number of fields in TIME log: " << sentence.body.size();
00118     throw ParseException(error.str());
00119   }
00120   bool valid = true;
00121   msg->clock_status = sentence.body[0];
00122   valid &= ParseDouble(sentence.body[1], msg->offset);
00123   valid &= ParseDouble(sentence.body[2], msg->offset_std);
00124   valid &= ParseDouble(sentence.body[3], msg->utc_offset);
00125   valid &= ParseUInt32(sentence.body[4], msg->utc_year, 10);
00126   valid &= ParseUInt8(sentence.body[5], msg->utc_month, 10);
00127   valid &= ParseUInt8(sentence.body[6], msg->utc_day, 10);
00128   valid &= ParseUInt8(sentence.body[7], msg->utc_hour, 10);
00129   valid &= ParseUInt8(sentence.body[8], msg->utc_minute, 10);
00130   valid &= ParseUInt32(sentence.body[9], msg->utc_millisecond, 10);
00131   msg->utc_status = sentence.body[10];
00132 
00133   if (!valid)
00134   {
00135     throw ParseException("Error parsing TIME log.");
00136   }
00137 
00138   return msg;
00139 }


novatel_gps_driver
Author(s):
autogenerated on Wed Jul 3 2019 19:40:37