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/heading2.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 Heading2Parser::MESSAGE_NAME = "HEADING2";
00039
00040 uint32_t Heading2Parser::GetMessageId() const
00041 {
00042 return MESSAGE_ID;
00043 }
00044
00045 const std::string Heading2Parser::GetMessageName() const
00046 {
00047 return MESSAGE_NAME;
00048 }
00049
00050 novatel_gps_msgs::NovatelHeading2Ptr Heading2Parser::ParseBinary(const BinaryMessage& bin_msg) throw(ParseException)
00051 {
00052 if (bin_msg.data_.size() != BINARY_LENGTH)
00053 {
00054 std::stringstream error;
00055 error << "Unexpected HEADING2 message length: " << bin_msg.data_.size();
00056 throw ParseException(error.str());
00057 }
00058 novatel_gps_msgs::NovatelHeading2Ptr ros_msg =
00059 boost::make_shared<novatel_gps_msgs::NovatelHeading2>();
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->baseline_length = ParseFloat(&bin_msg.data_[8]);
00083
00084 ros_msg->heading = ParseFloat(&bin_msg.data_[12]);
00085 ros_msg->pitch = ParseFloat(&bin_msg.data_[16]);
00086
00087
00088
00089 ros_msg->heading_sigma = ParseFloat(&bin_msg.data_[24]);
00090 ros_msg->pitch_sigma = ParseFloat(&bin_msg.data_[28]);
00091
00092 ros_msg->rover_station_id.resize(4);
00093 std::copy(&bin_msg.data_[32], &bin_msg.data_[36], &ros_msg->rover_station_id[0]);
00094
00095 ros_msg->master_station_id.resize(4);
00096 std::copy(&bin_msg.data_[36], &bin_msg.data_[40], &ros_msg->master_station_id[0]);
00097
00098 ros_msg->num_satellites_tracked = bin_msg.data_[40];
00099 ros_msg->num_satellites_used_in_solution = bin_msg.data_[41];
00100 ros_msg->num_satellites_above_elevation_mask_angle = bin_msg.data_[42];
00101 ros_msg->num_satellites_above_elevation_mask_angle_l2 = bin_msg.data_[43];
00102
00103 ros_msg->solution_source = SolutionSourceToMsgEnum(bin_msg.data_[44]);
00104
00105 GetExtendedSolutionStatusMessage(bin_msg.data_[45],
00106 ros_msg->extended_solution_status);
00107
00108
00109
00110 GetSignalsUsed(bin_msg.data_[47], ros_msg->signal_mask);
00111
00112 return ros_msg;
00113 }
00114
00115 novatel_gps_msgs::NovatelHeading2Ptr Heading2Parser::ParseAscii(const NovatelSentence& sentence) throw(ParseException)
00116 {
00117 novatel_gps_msgs::NovatelHeading2Ptr ros_msg =
00118 boost::make_shared<novatel_gps_msgs::NovatelHeading2>();
00119 HeaderParser h_parser;
00120 ros_msg->novatel_msg_header = h_parser.ParseAscii(sentence);
00121
00122 if (sentence.body.size() != ASCII_LENGTH)
00123 {
00124 std::stringstream error;
00125 error << "Unexpected number of HEADING2 message fields: " << sentence.body.size();
00126 throw ParseException(error.str());
00127 }
00128
00129 bool valid = true;
00130
00131 ros_msg->solution_status = sentence.body[0];
00132 ros_msg->position_type = sentence.body[1];
00133
00134 valid = valid && ParseFloat(sentence.body[2], ros_msg->baseline_length);
00135
00136 valid = valid && ParseFloat(sentence.body[3], ros_msg->heading);
00137 valid = valid && ParseFloat(sentence.body[4], ros_msg->pitch);
00138
00139
00140
00141 valid = valid && ParseFloat(sentence.body[6], ros_msg->heading_sigma);
00142 valid = valid && ParseFloat(sentence.body[7], ros_msg->pitch_sigma);
00143
00144 ros_msg->rover_station_id = sentence.body[8];
00145
00146 ros_msg->master_station_id = sentence.body[9];
00147
00148 valid = valid && ParseUInt8(sentence.body[10], ros_msg->num_satellites_tracked);
00149 valid = valid && ParseUInt8(sentence.body[11], ros_msg->num_satellites_used_in_solution);
00150 valid = valid && ParseUInt8(sentence.body[12], ros_msg->num_satellites_above_elevation_mask_angle);
00151 valid = valid && ParseUInt8(sentence.body[13], ros_msg->num_satellites_above_elevation_mask_angle_l2);
00152
00153 uint32_t solution_source = 0;
00154 valid = valid && ParseUInt32(sentence.body[14], solution_source, 16);
00155 ros_msg->solution_source = SolutionSourceToMsgEnum((uint8_t)solution_source);
00156
00157 uint32_t extended_solution_status = 0;
00158 valid = valid && ParseUInt32(sentence.body[15], extended_solution_status, 16);
00159 GetExtendedSolutionStatusMessage(
00160 extended_solution_status, ros_msg->extended_solution_status);
00161
00162
00163
00164 uint32_t signal_mask = 0;
00165 valid = valid && ParseUInt32(sentence.body[17], signal_mask, 16);
00166 GetSignalsUsed(signal_mask, ros_msg->signal_mask);
00167
00168 if (!valid)
00169 {
00170 throw ParseException("Invalid field in HEADING2 message");
00171 }
00172
00173 return ros_msg;
00174 }
00175
00176 uint8_t Heading2Parser::SolutionSourceToMsgEnum(uint8_t source_mask) throw(ParseException) {
00177 uint8_t source_bits = source_mask & 0b00001100;
00178 if (source_mask == 0b0000) {
00179 return novatel_gps_msgs::NovatelHeading2::SOURCE_PRIMARY_ANTENNA;
00180 } else if (source_mask == 0b0100) {
00181 return novatel_gps_msgs::NovatelHeading2::SOURCE_SECONDARY_ANTENNA;
00182 } else {
00183 throw ParseException("HEADING2 Solution Source could not be parsed due to unknown source");
00184 }
00185 }
00186 };