gpgsv.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/gpgsv.h>
00031 #include <boost/make_shared.hpp>
00032 
00033 const std::string novatel_gps_driver::GpgsvParser::MESSAGE_NAME = "GPGSV";
00034 
00035 uint32_t novatel_gps_driver::GpgsvParser::GetMessageId() const
00036 {
00037   return 0;
00038 }
00039 
00040 const std::string novatel_gps_driver::GpgsvParser::GetMessageName() const
00041 {
00042   return MESSAGE_NAME;
00043 }
00044 
00045 novatel_gps_msgs::GpgsvPtr novatel_gps_driver::GpgsvParser::ParseAscii(const novatel_gps_driver::NmeaSentence& sentence) throw(ParseException)
00046 {
00047   const size_t MIN_LENGTH = 4;
00048   // Check that the message is at least as long as a a GPGSV with no satellites
00049   if (sentence.body.size() < MIN_LENGTH)
00050   {
00051     std::stringstream error;
00052     error << "Expected GPGSV length >= " << MIN_LENGTH
00053           << ", actual length = " << sentence.body.size();
00054     throw ParseException(error.str());
00055   }
00056   novatel_gps_msgs::GpgsvPtr msg = boost::make_shared<novatel_gps_msgs::Gpgsv>();
00057   msg->message_id = sentence.body[0];
00058   if (!ParseUInt8(sentence.body[1], msg->n_msgs))
00059   {
00060     throw new ParseException("Error parsing n_msgs in GPGSV.");
00061   }
00062   if (msg->n_msgs > 9)  // Check that number of messages <= 9
00063   {
00064     std::stringstream error;
00065     error << "n_msgs in GPGSV was too large (" << msg->n_msgs << ").";
00066     throw ParseException(error.str());
00067   }
00068 
00069   if (!ParseUInt8(sentence.body[2], msg->msg_number))
00070   {
00071     throw ParseException("Error parsing msg_number in GPGSV.");
00072   }
00073   if (msg->msg_number > msg->n_msgs)  // Check that this message is within the sequence range
00074   {
00075     std::stringstream error;
00076     error << "msg_number in GPGSV was larger than n_msgs (" << msg->msg_number << " > " << msg->n_msgs << ").";
00077     throw ParseException(error.str());
00078   }
00079   if (!ParseUInt8(sentence.body[3], msg->n_satellites))
00080   {
00081     throw ParseException("Error parsing n_satellites in GPGSV.");
00082   }
00083 
00084 
00085   // Figure out how many satellites should be described in this sentence
00086   size_t n_sats_in_sentence = 4;
00087   if (msg->msg_number == msg->n_msgs)
00088   {
00089     n_sats_in_sentence = msg->n_satellites % static_cast<uint8_t>(4);
00090   }
00091   if (n_sats_in_sentence == 0)
00092   {
00093     n_sats_in_sentence = 4;
00094   }
00095   // Check that the sentence is the right length for the number of satellites
00096   size_t expected_length = MIN_LENGTH + 4 * n_sats_in_sentence;
00097   if (sentence.body.size() != expected_length && sentence.body.size() != expected_length -1)
00098   {
00099     std::stringstream ss;
00100     for (size_t i = 0; i < sentence.body.size(); ++i)
00101     {
00102       ss << sentence.body[i];
00103       if ((i+1) < sentence.body.size())
00104       {
00105         ss << ",";
00106       }
00107     }
00108     std::stringstream error;
00109     error << "Expected GPGSV length = " << expected_length << " for message with "
00110           << n_sats_in_sentence << " satellites, actual length = "
00111           << sentence.body.size() << "\n" << ss.str().c_str();
00112     throw ParseException(error.str());
00113   }
00114   msg->satellites.resize(n_sats_in_sentence);
00115   for (size_t sat = 0, index=MIN_LENGTH; sat < n_sats_in_sentence; ++sat, index += 4)
00116   {
00117     if (!ParseUInt8(sentence.body[index], msg->satellites[sat].prn))
00118     {
00119       std::stringstream error;
00120       error << "Error parsing prn for satellite " << sat << " in GPGSV.";
00121       throw ParseException(error.str());
00122     }
00123 
00124     float elevation;
00125     if (!ParseFloat(sentence.body[index + 1], elevation))
00126     {
00127       std::stringstream error;
00128       error << "Error parsing elevation for satellite " << sat << " in GPGSV.";
00129       throw ParseException(error.str());
00130     }
00131     msg->satellites[sat].elevation = static_cast<uint8_t>(elevation);
00132 
00133     float azimuth;
00134     if (!ParseFloat(sentence.body[index + 2], azimuth))
00135     {
00136       std::stringstream error;
00137       error << "Error parsing azimuth for satellite " << sat << " in GPGSV.";
00138       throw ParseException(error.str());
00139     }
00140     msg->satellites[sat].azimuth = static_cast<uint16_t>(azimuth);
00141 
00142     if ((index + 3) >= sentence.body.size() || sentence.body[index + 3].empty())
00143     {
00144       msg->satellites[sat].snr = -1;
00145     }
00146     else
00147     {
00148       uint8_t snr;
00149       if (!ParseUInt8(sentence.body[index + 3], snr))
00150       {
00151         std::stringstream error;
00152         error << "Error parsing snr for satellite " << sat << " in GPGSV.";
00153         throw ParseException(error.str());
00154       }
00155 
00156       msg->satellites[sat].snr = static_cast<int8_t>(snr);
00157     }
00158   }
00159   return msg;
00160 }


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