inspvax.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
31 #include <boost/make_shared.hpp>
33 
34 
35 const std::string novatel_gps_driver::InspvaxParser::MESSAGE_NAME = "INSPVAX";
36 
38 {
39  return MESSAGE_ID;
40 }
41 
43 {
44  return MESSAGE_NAME;
45 }
46 
47 novatel_gps_msgs::InspvaxPtr
49 {
50  if (bin_msg.data_.size() != BINARY_LENGTH)
51  {
52  std::stringstream error;
53  error << "Unexpected inspvax message size: " << bin_msg.data_.size();
54  throw ParseException(error.str());
55  }
56  novatel_gps_msgs::InspvaxPtr ros_msg = boost::make_shared<novatel_gps_msgs::Inspvax>();
57  HeaderParser h_parser;
58  ros_msg->novatel_msg_header = h_parser.ParseBinary(bin_msg);
59  ros_msg->novatel_msg_header.message_name = GetMessageName();
60 
61  uint16_t solution_status = ParseUInt16(&bin_msg.data_[0]);
62  if (solution_status > MAX_SOLUTION_STATUS)
63  {
64  std::stringstream error;
65  error << "Unknown solution status: " << solution_status;
66  throw ParseException(error.str());
67  }
68  ros_msg->ins_status = SOLUTION_STATUSES[solution_status];
69  uint16_t pos_type = ParseUInt16(&bin_msg.data_[4]);
70  if (pos_type > MAX_POSITION_TYPE)
71  {
72  std::stringstream error;
73  error << "Unknown position type: " << pos_type;
74  throw ParseException(error.str());
75  }
76  ros_msg->position_type = POSITION_TYPES[pos_type];
77 
78 
79 
80  ros_msg->latitude = ParseDouble(&bin_msg.data_[8]);
81  ros_msg->longitude = ParseDouble(&bin_msg.data_[16]);
82  ros_msg->altitude = ParseDouble(&bin_msg.data_[24]);
83  ros_msg->undulation = ParseFloat(&bin_msg.data_[32]);
84  ros_msg->north_velocity = ParseDouble(&bin_msg.data_[36]);
85  ros_msg->east_velocity = ParseDouble(&bin_msg.data_[44]);
86  ros_msg->up_velocity = ParseDouble(&bin_msg.data_[52]);
87  ros_msg->roll = ParseDouble(&bin_msg.data_[60]);
88  ros_msg->pitch = ParseDouble(&bin_msg.data_[68]);
89  ros_msg->azimuth = ParseDouble(&bin_msg.data_[76]);
90 
91  ros_msg->latitude_std = ParseFloat(&bin_msg.data_[84]);
92  ros_msg->longitude_std = ParseFloat(&bin_msg.data_[88]);
93  ros_msg->altitude_std = ParseFloat(&bin_msg.data_[92]);
94 
95  ros_msg->north_velocity_std = ParseFloat(&bin_msg.data_[96]);
96  ros_msg->east_velocity_std = ParseFloat(&bin_msg.data_[100]);
97  ros_msg->up_velocity_std = ParseFloat(&bin_msg.data_[104]);
98 
99  ros_msg->roll_std = ParseFloat(&bin_msg.data_[108]);
100  ros_msg->pitch_std = ParseFloat(&bin_msg.data_[112]);
101  ros_msg->azimuth_std = ParseFloat(&bin_msg.data_[116]);
102  GetExtendedSolutionStatusMessage(bin_msg.data_[120],
103  ros_msg->extended_status);
104  ros_msg->seconds_since_update = ParseUInt16(&bin_msg.data_[124]);
105 
106  return ros_msg;
107 }
108 
109 novatel_gps_msgs::InspvaxPtr
111 {
112  if (sentence.body.size() != ASCII_FIELDS)
113  {
114  std::stringstream error;
115  error << "Unexpected number of fields in INSPVA log: " << sentence.body.size();
116  throw ParseException(error.str());
117  }
118  novatel_gps_msgs::InspvaxPtr msg = boost::make_shared<novatel_gps_msgs::Inspvax>();
119  HeaderParser h_parser;
120  msg->novatel_msg_header = h_parser.ParseAscii(sentence);
121 
122  bool valid = true;
123 
124  msg->ins_status = sentence.body[0];
125  msg->position_type = sentence.body[1];
126  valid &= ParseDouble(sentence.body[2], msg->latitude);
127  valid &= ParseDouble(sentence.body[3], msg->longitude);
128  valid &= ParseDouble(sentence.body[4], msg->altitude);
129  valid &= ParseFloat(sentence.body[5], msg->undulation);
130  valid &= ParseDouble(sentence.body[6], msg->north_velocity);
131  valid &= ParseDouble(sentence.body[7], msg->east_velocity);
132  valid &= ParseDouble(sentence.body[8], msg->up_velocity);
133  valid &= ParseDouble(sentence.body[9], msg->roll);
134  valid &= ParseDouble(sentence.body[10], msg->pitch);
135  valid &= ParseDouble(sentence.body[11], msg->azimuth);
136  valid &= ParseFloat(sentence.body[12], msg->latitude_std);
137  valid &= ParseFloat(sentence.body[13], msg->longitude_std);
138  valid &= ParseFloat(sentence.body[14], msg->altitude_std);
139  valid &= ParseFloat(sentence.body[15], msg->north_velocity_std);
140  valid &= ParseFloat(sentence.body[16], msg->east_velocity_std);
141  valid &= ParseFloat(sentence.body[17], msg->up_velocity_std);
142  valid &= ParseFloat(sentence.body[18], msg->roll_std);
143  valid &= ParseFloat(sentence.body[19], msg->pitch_std);
144  valid &= ParseFloat(sentence.body[20], msg->azimuth_std);
145 
146  // skip reserved field
147  uint32_t extended_solution_status = 0;
148  valid = valid && ParseUInt32(sentence.body[21], extended_solution_status, 16);
150  extended_solution_status, msg->extended_status);
151 
152 
153  valid &= ParseUInt16(sentence.body[22], msg->seconds_since_update);
154 
155 
156  if (!valid)
157  {
158  throw ParseException("Error parsing INSPVAX log.");
159  }
160 
161  return msg;
162 }
163 
msg
novatel_gps_msgs::InspvaxPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
Definition: inspvax.cpp:110
uint16_t ParseUInt16(const uint8_t *buffer)
Converts a buffer containing 2 bytes into an unsigned 16-bit int.
static const std::string MESSAGE_NAME
Definition: inspvax.h:50
uint32_t GetMessageId() const override
Definition: inspvax.cpp:37
const size_t MAX_POSITION_TYPE
Definition: parsing_utils.h:56
const std::string GetMessageName() const override
Definition: inspvax.cpp:42
novatel_gps_msgs::NovatelMessageHeader ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
Definition: header.cpp:103
double ParseDouble(const uint8_t *buffer)
Converts a buffer containing 8 bytes into a double.
const std::string POSITION_TYPES[]
Definition: parsing_utils.h:57
novatel_gps_msgs::InspvaxPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: inspvax.cpp:48
uint32_t ParseUInt32(const uint8_t *buffer)
Converts a buffer containing 4 bytes into an unsigned 32-bit int.
float ParseFloat(const uint8_t *buffer)
Converts a buffer containing 4 bytes into a float.
const std::string SOLUTION_STATUSES[]
Definition: parsing_utils.h:50
void GetExtendedSolutionStatusMessage(uint32_t status, novatel_gps_msgs::NovatelExtendedSolutionStatus &msg)
const size_t MAX_SOLUTION_STATUS
Definition: parsing_utils.h:49
novatel_gps_msgs::NovatelMessageHeader ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: header.cpp:44
static constexpr uint32_t MESSAGE_ID
Definition: inspvax.h:49
static constexpr size_t BINARY_LENGTH
Definition: inspvax.h:51
static constexpr size_t ASCII_FIELDS
Definition: inspvax.h:52


novatel_gps_driver
Author(s):
autogenerated on Wed Jul 3 2019 19:36:46