bestxyz.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/bestxyz.h>
00031 
00032 #include <novatel_gps_driver/parsers/header.h>
00033 
00034 #include <boost/make_shared.hpp>
00035 
00036 namespace novatel_gps_driver
00037 {
00038   const std::string BestxyzParser::MESSAGE_NAME = "BESTXYZ";
00039 
00040   uint32_t BestxyzParser::GetMessageId() const
00041   {
00042     return MESSAGE_ID;
00043   }
00044 
00045   const std::string BestxyzParser::GetMessageName() const
00046   {
00047     return MESSAGE_NAME;
00048   }
00049 
00050   novatel_gps_msgs::NovatelXYZPtr BestxyzParser::ParseBinary(const BinaryMessage& bin_msg) throw(ParseException) 
00051   {
00052     if (bin_msg.data_.size() != BINARY_LENGTH)
00053     {
00054       std::stringstream error;
00055       error << "Unexpected BESTXYZ message length: " << bin_msg.data_.size();
00056       throw ParseException(error.str());
00057     }
00058     novatel_gps_msgs::NovatelXYZPtr ros_msg =
00059         boost::make_shared<novatel_gps_msgs::NovatelXYZ>();
00060     HeaderParser header_parser;
00061     ros_msg->novatel_msg_header = header_parser.ParseBinary(bin_msg);
00062     ros_msg->novatel_msg_header.message_name = MESSAGE_NAME;
00063 
00064     uint16_t solution_status = ParseUInt16(&bin_msg.data_[0]);
00065     if (solution_status > MAX_SOLUTION_STATUS)
00066     {
00067       std::stringstream error;
00068       error << "Unknown solution status: " << solution_status;
00069       throw ParseException(error.str());
00070     }
00071     ros_msg->solution_status = SOLUTION_STATUSES[solution_status];
00072     
00073     uint16_t pos_type = ParseUInt16(&bin_msg.data_[4]);
00074     if (pos_type > MAX_POSITION_TYPE)
00075     {
00076       std::stringstream error;
00077       error << "Unknown position type: " << pos_type;
00078       throw ParseException(error.str());
00079     }
00080     ros_msg->position_type = POSITION_TYPES[pos_type];
00081 
00082     ros_msg->x = ParseDouble(&bin_msg.data_[8]);
00083     ros_msg->y = ParseDouble(&bin_msg.data_[16]);
00084     ros_msg->z = ParseDouble(&bin_msg.data_[24]);
00085 
00086     ros_msg->x_sigma = ParseFloat(&bin_msg.data_[32]);
00087     ros_msg->y_sigma = ParseFloat(&bin_msg.data_[36]);
00088     ros_msg->z_sigma = ParseFloat(&bin_msg.data_[40]);
00089 
00090     uint16_t vel_solution_status = ParseUInt16(&bin_msg.data_[44]);
00091     if (vel_solution_status > MAX_SOLUTION_STATUS)
00092     {
00093       std::stringstream error;
00094       error << "Unknown solution status: " << vel_solution_status;
00095       throw ParseException(error.str());
00096     }
00097     ros_msg->velocity_solution_status = SOLUTION_STATUSES[vel_solution_status];
00098 
00099     uint16_t vel_type = ParseUInt16(&bin_msg.data_[48]);
00100     if (vel_type > MAX_POSITION_TYPE) // Position types array includes velocity types
00101     {
00102       std::stringstream error;
00103       error << "Unknown position type: " << vel_type;
00104       throw ParseException(error.str());
00105     }
00106     ros_msg->velocity_type = POSITION_TYPES[vel_type];
00107 
00108     ros_msg->x_vel = ParseDouble(&bin_msg.data_[52]);
00109     ros_msg->y_vel = ParseDouble(&bin_msg.data_[60]);
00110     ros_msg->z_vel = ParseDouble(&bin_msg.data_[68]);
00111 
00112     ros_msg->x_vel_sigma = ParseFloat(&bin_msg.data_[76]);
00113     ros_msg->y_vel_sigma = ParseFloat(&bin_msg.data_[80]);
00114     ros_msg->z_vel_sigma = ParseFloat(&bin_msg.data_[84]);
00115 
00116     ros_msg->base_station_id.resize(4);
00117     std::copy(&bin_msg.data_[88], &bin_msg.data_[92], &ros_msg->base_station_id[0]);
00118 
00119     ros_msg->velocity_latency = ParseFloat(&bin_msg.data_[92]);
00120 
00121     ros_msg->diff_age = ParseFloat(&bin_msg.data_[96]);
00122     ros_msg->solution_age = ParseFloat(&bin_msg.data_[100]);
00123 
00124     ros_msg->num_satellites_tracked = bin_msg.data_[104];
00125     ros_msg->num_satellites_used_in_solution = bin_msg.data_[105];
00126     ros_msg->num_gps_and_glonass_l1_used_in_solution = bin_msg.data_[106];
00127     ros_msg->num_gps_and_glonass_l1_and_l2_used_in_solution = bin_msg.data_[107];
00128     // Byte 108 is reserved
00129     GetExtendedSolutionStatusMessage(bin_msg.data_[109],
00130                                      ros_msg->extended_solution_status);
00131     // Byte 110 is reserved
00132     GetSignalsUsed(bin_msg.data_[111], ros_msg->signal_mask);
00133 
00134     return ros_msg;
00135   }
00136 
00137   novatel_gps_msgs::NovatelXYZPtr BestxyzParser::ParseAscii(const NovatelSentence& sentence) throw(ParseException)
00138   {
00139     novatel_gps_msgs::NovatelXYZPtr msg =
00140         boost::make_shared<novatel_gps_msgs::NovatelXYZ>();
00141     HeaderParser h_parser;
00142     msg->novatel_msg_header = h_parser.ParseAscii(sentence);
00143 
00144     if (sentence.body.size() != ASCII_LENGTH)
00145     {
00146       std::stringstream error;
00147       error << "Unexpected number of BESTXYZ message fields: " << sentence.body.size();
00148       throw ParseException(error.str());
00149     }
00150 
00151     bool valid = true;
00152 
00153     msg->solution_status = sentence.body[0];
00154     msg->position_type = sentence.body[1];
00155     
00156     valid = valid && ParseDouble(sentence.body[2], msg->x);
00157     valid = valid && ParseDouble(sentence.body[3], msg->y);
00158     valid = valid && ParseDouble(sentence.body[4], msg->z);
00159 
00160     valid = valid && ParseFloat(sentence.body[5], msg->x_sigma);
00161     valid = valid && ParseFloat(sentence.body[6], msg->y_sigma);
00162     valid = valid && ParseFloat(sentence.body[7], msg->z_sigma);
00163 
00164     msg->velocity_solution_status = sentence.body[8];
00165     msg->velocity_type = sentence.body[9];
00166 
00167     valid = valid && ParseDouble(sentence.body[10], msg->x_vel);
00168     valid = valid && ParseDouble(sentence.body[11], msg->y_vel);
00169     valid = valid && ParseDouble(sentence.body[12], msg->z_vel);
00170 
00171     valid = valid && ParseFloat(sentence.body[13], msg->x_vel_sigma);
00172     valid = valid && ParseFloat(sentence.body[14], msg->y_vel_sigma);
00173     valid = valid && ParseFloat(sentence.body[15], msg->z_vel_sigma);
00174 
00175     msg->base_station_id = sentence.body[16];
00176     valid = valid && ParseFloat(sentence.body[17], msg->velocity_latency);
00177     
00178     valid = valid && ParseFloat(sentence.body[18], msg->diff_age);
00179     valid = valid && ParseFloat(sentence.body[19], msg->solution_age);
00180     valid = valid && ParseUInt8(sentence.body[20], msg->num_satellites_tracked);
00181     valid = valid && ParseUInt8(sentence.body[21], msg->num_satellites_used_in_solution);
00182     valid = valid && ParseUInt8(sentence.body[22], msg->num_gps_and_glonass_l1_used_in_solution);
00183     valid = valid && ParseUInt8(sentence.body[23], msg->num_gps_and_glonass_l1_and_l2_used_in_solution);
00184 
00185     // skip reserved field
00186     uint32_t extended_solution_status = 0;
00187     valid = valid && ParseUInt32(sentence.body[25], extended_solution_status, 16);
00188     GetExtendedSolutionStatusMessage(
00189         extended_solution_status, msg->extended_solution_status);
00190 
00191     // skip reserved field
00192     uint32_t signal_mask = 0;
00193     valid = valid && ParseUInt32(sentence.body[27], signal_mask, 16);
00194     GetSignalsUsed(signal_mask, msg->signal_mask);
00195 
00196     if (!valid)
00197     {
00198       throw ParseException("Invalid field in BESTXYZ message");
00199     }
00200 
00201     return msg;
00202   }
00203 };


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