Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <novatel_gps_driver/parsers/inspvax.h>
00031 #include <boost/make_shared.hpp>
00032 #include <novatel_gps_driver/parsers/header.h>
00033
00034
00035 const std::string novatel_gps_driver::InspvaxParser::MESSAGE_NAME = "INSPVAX";
00036
00037 uint32_t novatel_gps_driver::InspvaxParser::GetMessageId() const
00038 {
00039 return MESSAGE_ID;
00040 }
00041
00042 const std::string novatel_gps_driver::InspvaxParser::GetMessageName() const
00043 {
00044 return MESSAGE_NAME;
00045 }
00046
00047 novatel_gps_msgs::InspvaxPtr
00048 novatel_gps_driver::InspvaxParser::ParseBinary(const novatel_gps_driver::BinaryMessage& bin_msg) throw(ParseException)
00049 {
00050 if (bin_msg.data_.size() != BINARY_LENGTH)
00051 {
00052 std::stringstream error;
00053 error << "Unexpected inspvax message size: " << bin_msg.data_.size();
00054 throw ParseException(error.str());
00055 }
00056 novatel_gps_msgs::InspvaxPtr ros_msg = boost::make_shared<novatel_gps_msgs::Inspvax>();
00057 HeaderParser h_parser;
00058 ros_msg->novatel_msg_header = h_parser.ParseBinary(bin_msg);
00059 ros_msg->novatel_msg_header.message_name = GetMessageName();
00060
00061 uint16_t solution_status = ParseUInt16(&bin_msg.data_[0]);
00062 if (solution_status > MAX_SOLUTION_STATUS)
00063 {
00064 std::stringstream error;
00065 error << "Unknown solution status: " << solution_status;
00066 throw ParseException(error.str());
00067 }
00068 ros_msg->ins_status = SOLUTION_STATUSES[solution_status];
00069 uint16_t pos_type = ParseUInt16(&bin_msg.data_[4]);
00070 if (pos_type > MAX_POSITION_TYPE)
00071 {
00072 std::stringstream error;
00073 error << "Unknown position type: " << pos_type;
00074 throw ParseException(error.str());
00075 }
00076 ros_msg->position_type = POSITION_TYPES[pos_type];
00077
00078
00079
00080 ros_msg->latitude = ParseDouble(&bin_msg.data_[8]);
00081 ros_msg->longitude = ParseDouble(&bin_msg.data_[16]);
00082 ros_msg->altitude = ParseDouble(&bin_msg.data_[24]);
00083 ros_msg->undulation = ParseFloat(&bin_msg.data_[32]);
00084 ros_msg->north_velocity = ParseDouble(&bin_msg.data_[36]);
00085 ros_msg->east_velocity = ParseDouble(&bin_msg.data_[44]);
00086 ros_msg->up_velocity = ParseDouble(&bin_msg.data_[52]);
00087 ros_msg->roll = ParseDouble(&bin_msg.data_[60]);
00088 ros_msg->pitch = ParseDouble(&bin_msg.data_[68]);
00089 ros_msg->azimuth = ParseDouble(&bin_msg.data_[76]);
00090
00091 ros_msg->latitude_std = ParseFloat(&bin_msg.data_[84]);
00092 ros_msg->longitude_std = ParseFloat(&bin_msg.data_[88]);
00093 ros_msg->altitude_std = ParseFloat(&bin_msg.data_[92]);
00094
00095 ros_msg->north_velocity_std = ParseFloat(&bin_msg.data_[96]);
00096 ros_msg->east_velocity_std = ParseFloat(&bin_msg.data_[100]);
00097 ros_msg->up_velocity_std = ParseFloat(&bin_msg.data_[104]);
00098
00099 ros_msg->roll_std = ParseFloat(&bin_msg.data_[108]);
00100 ros_msg->pitch_std = ParseFloat(&bin_msg.data_[112]);
00101 ros_msg->azimuth_std = ParseFloat(&bin_msg.data_[116]);
00102 GetExtendedSolutionStatusMessage(bin_msg.data_[120],
00103 ros_msg->extended_status);
00104 ros_msg->seconds_since_update = ParseUInt16(&bin_msg.data_[124]);
00105
00106 return ros_msg;
00107 }
00108
00109 novatel_gps_msgs::InspvaxPtr
00110 novatel_gps_driver::InspvaxParser::ParseAscii(const novatel_gps_driver::NovatelSentence& sentence) throw(ParseException)
00111 {
00112 if (sentence.body.size() != ASCII_FIELDS)
00113 {
00114 std::stringstream error;
00115 error << "Unexpected number of fields in INSPVA log: " << sentence.body.size();
00116 throw ParseException(error.str());
00117 }
00118 novatel_gps_msgs::InspvaxPtr msg = boost::make_shared<novatel_gps_msgs::Inspvax>();
00119 HeaderParser h_parser;
00120 msg->novatel_msg_header = h_parser.ParseAscii(sentence);
00121
00122 bool valid = true;
00123
00124 msg->ins_status = sentence.body[0];
00125 msg->position_type = sentence.body[1];
00126 valid &= ParseDouble(sentence.body[2], msg->latitude);
00127 valid &= ParseDouble(sentence.body[3], msg->longitude);
00128 valid &= ParseDouble(sentence.body[4], msg->altitude);
00129 valid &= ParseFloat(sentence.body[5], msg->undulation);
00130 valid &= ParseDouble(sentence.body[6], msg->north_velocity);
00131 valid &= ParseDouble(sentence.body[7], msg->east_velocity);
00132 valid &= ParseDouble(sentence.body[8], msg->up_velocity);
00133 valid &= ParseDouble(sentence.body[9], msg->roll);
00134 valid &= ParseDouble(sentence.body[10], msg->pitch);
00135 valid &= ParseDouble(sentence.body[11], msg->azimuth);
00136 valid &= ParseFloat(sentence.body[12], msg->latitude_std);
00137 valid &= ParseFloat(sentence.body[13], msg->longitude_std);
00138 valid &= ParseFloat(sentence.body[14], msg->altitude_std);
00139 valid &= ParseFloat(sentence.body[15], msg->north_velocity_std);
00140 valid &= ParseFloat(sentence.body[16], msg->east_velocity_std);
00141 valid &= ParseFloat(sentence.body[17], msg->up_velocity_std);
00142 valid &= ParseFloat(sentence.body[18], msg->roll_std);
00143 valid &= ParseFloat(sentence.body[19], msg->pitch_std);
00144 valid &= ParseFloat(sentence.body[20], msg->azimuth_std);
00145
00146
00147 uint32_t extended_solution_status = 0;
00148 valid = valid && ParseUInt32(sentence.body[21], extended_solution_status, 16);
00149 GetExtendedSolutionStatusMessage(
00150 extended_solution_status, msg->extended_status);
00151
00152
00153 valid &= ParseUInt16(sentence.body[22], msg->seconds_since_update);
00154
00155
00156 if (!valid)
00157 {
00158 throw ParseException("Error parsing INSPVAX log.");
00159 }
00160
00161 return msg;
00162 }
00163