oem7_message_util.hpp
Go to the documentation of this file.
1 //
3 // Copyright (c) 2020 NovAtel Inc.
4 //
5 // Permission is hereby granted, free of charge, to any person obtaining a copy
6 // of this software and associated documentation files (the "Software"), to deal
7 // in the Software without restriction, including without limitation the rights
8 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 // copies of the Software, and to permit persons to whom the Software is
10 // furnished to do so, subject to the following conditions:
11 //
12 // The above copyright notice and this permission notice shall be included in all
13 // copies or substantial portions of the Software.
14 //
15 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 // SOFTWARE.
22 //
24 
25 #ifndef __OEM7_MESSAGE_UTIL_HPP__
26 #define __OEM7_MESSAGE_UTIL_HPP__
27 
28 #include "novatel_oem7_msgs/Oem7Header.h"
29 #include "novatel_oem7_msgs/Oem7RawMsg.h"
30 
32 
33 #include "oem7_raw_message_if.hpp"
35 
36 #include "oem7_messages.h"
37 
38 #include <ros/ros.h>
39 
40 namespace novatel_oem7_driver
41 {
42 
43  static const std::vector<int> OEM7_NMEA_MSGIDS(
44  {
60  }
61  );
62 
63 
65  int getOem7MessageId(const std::string& msg_name);
66  const std::string& getOem7MessageName(int msg_id);
67 
72  void getOem7Header(
73  const Oem7RawMessageIf::ConstPtr& raw_msg,
74  novatel_oem7_msgs::Oem7Header::Type& hdr
75  );
76 
81  void getOem7ShortHeader(
82  const Oem7RawMessageIf::ConstPtr& raw_msg,
83  novatel_oem7_msgs::Oem7Header::Type& hdr
84  );
85 
86  bool isNMEAMessage(const Oem7RawMessageIf::ConstPtr& raw_msg);
87 
88  size_t Get_INSCONFIG_NumTranslations(const INSCONFIG_FixedMem* insconfig);
89 
90  const INSCONFIG_TranslationMem* Get_INSCONFIG_Translation(const INSCONFIG_FixedMem* insconfig, size_t idx);
91 
92  size_t Get_INSCONFIG_NumRotations(const INSCONFIG_FixedMem* insconfig);
93 
94  const INSCONFIG_RotationMem* Get_INSCONFIG_Rotation(const INSCONFIG_FixedMem* insconfig, size_t idx);
95 
96 
97  size_t Get_PSRDOP2_NumSystems(const PSRDOP2_FixedMem* psrdop2);
98  const PSRDOP2_SystemMem* Get_PSRDOP2_System(const PSRDOP2_FixedMem* psrdop2, size_t idx);
99 }
100 
101 
102 #endif
static const std::vector< int > OEM7_NMEA_MSGIDS({GLMLA_OEM7_MSGID, GPALM_OEM7_MSGID, GPGGA_OEM7_MSGID, GPGGALONG_OEM7_MSGID, GPGLL_OEM7_MSGID, GPGRS_OEM7_MSGID, GPGSA_OEM7_MSGID, GPGST_OEM7_MSGID, GPGSV_OEM7_MSGID, GPHDT_OEM7_MSGID, GPHDTDUALANTENNA_MSGID, GPRMB_OEM7_MSGID, GPRMC_OEM7_MSGID, GPVTG_OEM7_MSGID, GPZDA_OEM7_MSGID})
const PSRDOP2_SystemMem * Get_PSRDOP2_System(const PSRDOP2_FixedMem *psrdop2, size_t idx)
bool isNMEAMessage(const Oem7RawMessageIf::ConstPtr &raw_msg)
size_t Get_INSCONFIG_NumTranslations(const INSCONFIG_FixedMem *insconfig)
const INSCONFIG_TranslationMem * Get_INSCONFIG_Translation(const INSCONFIG_FixedMem *insconfig, size_t idx)
int getOem7MessageId(const std::string &msg_name)
size_t Get_PSRDOP2_NumSystems(const PSRDOP2_FixedMem *psrdop2)
void getOem7ShortHeader(const Oem7RawMessageIf::ConstPtr &raw_msg, novatel_oem7_msgs::Oem7Header::Type &hdr)
size_t Get_INSCONFIG_NumRotations(const INSCONFIG_FixedMem *insconfig)
void getOem7Header(const Oem7RawMessageIf::ConstPtr &raw_msg, novatel_oem7_msgs::Oem7Header::Type &hdr)
void initializeOem7MessageUtil(ros::NodeHandle &nh)
const std::string & getOem7MessageName(int msg_id)
const int GPHDTDUALANTENNA_MSGID
const int GPGGALONG_OEM7_MSGID
const INSCONFIG_RotationMem * Get_INSCONFIG_Rotation(const INSCONFIG_FixedMem *insconfig, size_t idx)


novatel_oem7_driver
Author(s):
autogenerated on Tue Mar 9 2021 03:48:00