rx_message.hpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // © Copyright 2020, Septentrio NV/SA.
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 // 1. Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // 2. 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 // 3. Neither the name of the copyright holder nor the names of its
14 // contributors may be used to endorse or promote products derived
15 // 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 THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 // *****************************************************************************
30 
31 // *****************************************************************************
32 //
33 // Boost Software License - Version 1.0 - August 17th, 2003
34 //
35 // Permission is hereby granted, free of charge, to any person or organization
36 // obtaining a copy of the software and accompanying documentation covered by
37 // this license (the "Software") to use, reproduce, display, distribute,
38 // execute, and transmit the Software, and to prepare derivative works of the
39 // Software, and to permit third-parties to whom the Software is furnished to
40 // do so, all subject to the following:
41 
42 // The copyright notices in the Software and this entire statement, including
43 // the above license grant, this restriction and the following disclaimer,
44 // must be included in all copies of the Software, in whole or in part, and
45 // all derivative works of the Software, unless such copies or derivative
46 // works are solely in the form of machine-executable object code generated by
47 // a source language processor.
48 //
49 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
50 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
51 // FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT
52 // SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE
53 // FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE,
54 // ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
55 // DEALINGS IN THE SOFTWARE.
56 //
57 // *****************************************************************************
58 
60 #ifndef NMEA_SYNC_BYTE_1
61 #define NMEA_SYNC_BYTE_1 0x24
62 #endif
63 #ifndef NMEA_SYNC_BYTE_2_1
65 #define NMEA_SYNC_BYTE_2_1 0x47
66 #endif
67 #ifndef NMEA_SYNC_BYTE_2_2
69 #define NMEA_SYNC_BYTE_2_2 0x50
70 #endif
71 #ifndef RESPONSE_SYNC_BYTE_1
73 #define RESPONSE_SYNC_BYTE_1 0x24
74 #endif
75 #ifndef RESPONSE_SYNC_BYTE_2
77 #define RESPONSE_SYNC_BYTE_2 0x52
78 #endif
79 #ifndef CARRIAGE_RETURN
81 #define CARRIAGE_RETURN 0x0D
82 #endif
83 #ifndef LINE_FEED
85 #define LINE_FEED 0x0A
86 #endif
87 #ifndef RESPONSE_SYNC_BYTE_3
90 #define RESPONSE_SYNC_BYTE_3 0x3F
91 #endif
92 #ifndef CONNECTION_DESCRIPTOR_BYTE_1
95 #define CONNECTION_DESCRIPTOR_BYTE_1 0x49
96 #endif
97 #ifndef CONNECTION_DESCRIPTOR_BYTE_2
100 #define CONNECTION_DESCRIPTOR_BYTE_2 0x50
101 #endif
102 
103 // C++ libraries
104 #include <cassert> // for assert
105 #include <cstddef>
106 #include <map>
107 #include <sstream>
108 // Boost includes
109 #include <boost/call_traits.hpp>
110 #include <boost/format.hpp>
111 #include <boost/math/constants/constants.hpp>
112 #include <boost/tokenizer.hpp>
113 // ROSaic includes
121 
122 #ifndef RX_MESSAGE_HPP
123 #define RX_MESSAGE_HPP
124 
131 extern bool g_read_cd;
132 extern uint32_t g_cd_count;
133 
135 struct Settings
136 {
140  std::string device;
142  std::string login_user;
144  std::string login_password;
149  uint32_t baudrate;
151  std::string hw_flow_control;
154  std::string rx_serial_port;
156  std::string datum;
162  float delta_e;
164  float delta_n;
166  float delta_u;
169  std::string ant_type;
172  std::string ant_aux1_type;
174  std::string ant_serial_nr;
176  std::string ant_aux1_serial_nr;
180  double theta_x;
182  double theta_y;
184  double theta_z;
186  double ant_lever_x;
188  double ant_lever_y;
190  double ant_lever_z;
192  double poi_x;
194  double poi_y;
196  double poi_z;
198  double vsm_x;
200  double vsm_y;
202  double vsm_z;
206  double pitch_offset;
212  std::string ins_initial_heading;
214  float att_std_dev;
216  float pos_std_dev;
218  std::string ntrip_mode;
220  std::string caster;
222  uint32_t caster_port;
224  std::string ntrip_username;
226  std::string ntrip_password;
228  std::string mountpoint;
230  std::string ntrip_version;
234  std::string rtcm_version;
242  std::string send_gga;
308  std::string frame_id;
310  std::string imu_frame_id;
312  std::string poi_frame_id;
314  std::string vsm_frame_id;
316  std::string aux1_frame_id;
318  std::string vehicle_frame_id;
322  uint32_t leap_seconds;
327 };
328 
332 {
343 };
344 
349 {
385 };
386 
387 namespace io_comm_rx {
388 
393  class RxMessage
394  {
395  public:
406  RxMessage(ROSaicNodeBase* node, Settings* settings) :
407  node_(node),
408  settings_(settings),
409  unix_time_(0)
410  {
411  found_ = false;
412  crc_check_ = false;
413  message_size_ = 0;
414 
416  std::pair<uint16_t, TypeOfPVT_Enum> type_of_pvt_pairs[] = {
417  std::make_pair(static_cast<uint16_t>(0), evNoPVT),
418  std::make_pair(static_cast<uint16_t>(1), evStandAlone),
419  std::make_pair(static_cast<uint16_t>(2), evDGPS),
420  std::make_pair(static_cast<uint16_t>(3), evFixed),
421  std::make_pair(static_cast<uint16_t>(4), evRTKFixed),
422  std::make_pair(static_cast<uint16_t>(5), evRTKFloat),
423  std::make_pair(static_cast<uint16_t>(6), evSBAS),
424  std::make_pair(static_cast<uint16_t>(7), evMovingBaseRTKFixed),
425  std::make_pair(static_cast<uint16_t>(8), evMovingBaseRTKFloat),
426  std::make_pair(static_cast<uint16_t>(10), evPPP)};
427 
428  type_of_pvt_map = TypeOfPVTMap(type_of_pvt_pairs, type_of_pvt_pairs + evPPP + 1);
429 
431  std::pair<std::string, RxID_Enum> rx_id_pairs[] = {
432  std::make_pair("NavSatFix", evNavSatFix),
433  std::make_pair("INSNavSatFix", evINSNavSatFix),
434  std::make_pair("GPSFix", evGPSFix),
435  std::make_pair("INSGPSFix", evINSGPSFix),
436  std::make_pair("PoseWithCovarianceStamped", evPoseWithCovarianceStamped),
437  std::make_pair("INSPoseWithCovarianceStamped", evINSPoseWithCovarianceStamped),
438  std::make_pair("$GPGGA", evGPGGA),
439  std::make_pair("$GPRMC", evGPRMC),
440  std::make_pair("$GPGSA", evGPGSA),
441  std::make_pair("$GPGSV", evGPGSV),
442  std::make_pair("$GLGSV", evGLGSV),
443  std::make_pair("$GAGSV", evGAGSV),
444  std::make_pair("4006", evPVTCartesian),
445  std::make_pair("4007", evPVTGeodetic),
446  std::make_pair("5905", evPosCovCartesian),
447  std::make_pair("5906", evPosCovGeodetic),
448  std::make_pair("5938", evAttEuler),
449  std::make_pair("5939", evAttCovEuler),
450  std::make_pair("GPST", evGPST),
451  std::make_pair("4013", evChannelStatus),
452  std::make_pair("4027", evMeasEpoch),
453  std::make_pair("4001", evDOP),
454  std::make_pair("5908", evVelCovGeodetic),
455  std::make_pair("DiagnosticArray", evDiagnosticArray),
456  std::make_pair("Localization", evLocalization),
457  std::make_pair("4014", evReceiverStatus),
458  std::make_pair("4082", evQualityInd),
459  std::make_pair("5902", evReceiverSetup),
460  std::make_pair("4225", evINSNavCart),
461  std::make_pair("4226", evINSNavGeod),
462  std::make_pair("4230", evExtEventINSNavGeod),
463  std::make_pair("4229", evExtEventINSNavCart),
464  std::make_pair("4224", evIMUSetup),
465  std::make_pair("4244", evVelSensorSetup),
466  std::make_pair("4050", evExtSensorMeas)
467  };
468 
469  rx_id_map = RxIDMap(rx_id_pairs, rx_id_pairs + evReceiverSetup + 1);
470  }
471 
478  void newData(Timestamp recvTimestamp, const uint8_t* data, std::size_t& size)
479  {
480  recvTimestamp_ = recvTimestamp;
481  data_ = data;
482  count_ = size;
483  found_ = false;
484  crc_check_ = false;
485  message_size_ = 0;
486  }
487 
489  bool isMessage(const uint16_t ID);
492  bool isMessage(std::string ID);
494  bool isSBF();
496  bool isNMEA();
498  bool isResponse();
501  bool isConnectionDescriptor();
504  bool isErrorMessage();
507  std::size_t messageSize();
510  std::string messageID();
511 
516  std::size_t getCount() { return count_; };
522  const uint8_t* search();
523 
531  uint16_t getBlockLength();
532 
537  const uint8_t* getPosBuffer();
538 
544  const uint8_t* getEndBuffer();
545 
551  bool found();
552 
557  void next();
558 
563  bool read(std::string message_key, bool search = false);
564 
568  bool found_;
569 
573  bool gnss_gpsfix_complete(uint32_t id);
574 
578  bool ins_gpsfix_complete(uint32_t id);
579 
583  bool gnss_navsatfix_complete(uint32_t id);
584 
588  bool ins_navsatfix_complete(uint32_t id);
589 
593  bool gnss_pose_complete(uint32_t id);
594 
598  bool ins_pose_complete(uint32_t id);
599 
603  bool diagnostics_complete(uint32_t id);
604 
608  bool ins_localization_complete(uint32_t id);
609 
610  private:
615 
620 
624  const uint8_t* data_;
625 
629  std::size_t count_;
630 
636 
641  std::size_t message_size_;
642 
646  uint32_t count_gpsfix_ = 0;
647 
653 
659 
665 
671 
677 
683 
689 
695 
700 
706 
712 
718 
724 
727  typedef std::unordered_map<uint16_t, TypeOfPVT_Enum> TypeOfPVTMap;
728 
733  TypeOfPVTMap type_of_pvt_map;
734 
737  typedef std::unordered_map<std::string, RxID_Enum> RxIDMap;
738 
747  RxIDMap rx_id_map;
748 
752 
755  bool channelstatus_has_arrived_gpsfix_ = false;
756 
758  bool measepoch_has_arrived_gpsfix_ = false;
759 
761  bool dop_has_arrived_gpsfix_ = false;
762 
764  bool pvtgeodetic_has_arrived_gpsfix_ = false;
765 
768  bool poscovgeodetic_has_arrived_gpsfix_ = false;
769 
772  bool velcovgeodetic_has_arrived_gpsfix_ = false;
773 
775  bool atteuler_has_arrived_gpsfix_ = false;
776 
778  bool attcoveuler_has_arrived_gpsfix_ = false;
779 
781  bool insnavgeod_has_arrived_gpsfix_ = false;
782 
785  bool pvtgeodetic_has_arrived_navsatfix_ = false;
786 
789  bool poscovgeodetic_has_arrived_navsatfix_ = false;
790 
793  bool insnavgeod_has_arrived_navsatfix_ = false;
796  bool pvtgeodetic_has_arrived_pose_ = false;
797 
800  bool poscovgeodetic_has_arrived_pose_ = false;
801 
804  bool atteuler_has_arrived_pose_ = false;
805 
808  bool attcoveuler_has_arrived_pose_ = false;
809 
812  bool insnavgeod_has_arrived_pose_ = false;
813 
816  bool receiverstatus_has_arrived_diagnostics_ = false;
817 
820  bool qualityind_has_arrived_diagnostics_ = false;
821 
824  bool insnavgeod_has_arrived_localization_ = false;
825 
830  NavSatFixMsg NavSatFixCallback();
831 
836  GPSFixMsg GPSFixCallback();
837 
845  PoseWithCovarianceStampedCallback();
846 
853  DiagnosticArrayMsg DiagnosticArrayCallback();
854 
861  ImuMsg ImuCallback();
862 
869  LocalizationUtmMsg LocalizationUtmCallback();
870 
874  void wait(Timestamp time_obj);
875 
879  bool allTrue(std::vector<bool>& vec, uint32_t id);
880 
885 
889  std::shared_ptr<std::string> fixedUtmZone_;
890 
900  Timestamp timestampSBF(const uint8_t* data, bool use_gnss_time);
901 
914  Timestamp timestampSBF(uint32_t tow, uint16_t wnc, bool use_gnss_time);
915  };
916 } // namespace io_comm_rx
917 #endif // for RX_MESSAGE_HPP
double theta_z
IMU orientation z-angle.
Definition: rx_message.hpp:184
septentrio_gnss_driver::VelCovGeodetic VelCovGeodeticMsg
Definition: typedefs.hpp:107
Derived class for parsing GSA messages.
Timestamp recvTimestamp_
Timestamp of receiving buffer.
Definition: rx_message.hpp:619
uint32_t polling_period_rest
Polling period for all other SBF blocks and NMEA messages.
Definition: rx_message.hpp:160
AttCovEulerMsg last_attcoveuler_
Since GPSFix etc. need AttCovEuler, incoming AttCovEuler blocks need to be stored.
Definition: rx_message.hpp:670
std::string vehicle_frame_id
The frame ID of the vehicle frame.
Definition: rx_message.hpp:318
const uint8_t * data_
Pointer to the buffer of messages.
Definition: rx_message.hpp:624
PosCovGeodeticMsg last_poscovgeodetic_
Since NavSatFix etc. need PosCovGeodetic, incoming PosCovGeodetic blocks need to be stored...
Definition: rx_message.hpp:658
septentrio_gnss_driver::AttCovEuler AttCovEulerMsg
Definition: typedefs.hpp:100
bool publish_insnavcart
Whether or not to publish the INSNavCartMsg message.
Definition: rx_message.hpp:272
bool publish_attcoveuler
Whether or not to publish the AttCovEulerMsg message.
Definition: rx_message.hpp:270
float delta_e
Marker-to-ARP offset in the eastward direction.
Definition: rx_message.hpp:162
bool publish_tf
Whether or not to publish the tf of the localization.
Definition: rx_message.hpp:300
bool read_from_sbf_log
Whether or not we are reading from an SBF file.
Definition: rx_message.hpp:324
std::string hw_flow_control
HW flow control.
Definition: rx_message.hpp:151
uint32_t leap_seconds
The number of leap seconds that have been inserted into the UTC time.
Definition: rx_message.hpp:322
bool publish_poscovgeodetic
Definition: rx_message.hpp:263
PVTGeodeticMsg last_pvtgeodetic_
Since NavSatFix etc. need PVTGeodetic, incoming PVTGeodetic blocks need to be stored.
Definition: rx_message.hpp:652
bool crc_check_
Whether the CRC check as evaluated in the read() method was successful or not is stored here...
Definition: rx_message.hpp:635
double poi_x
INS POI offset in x-dimension.
Definition: rx_message.hpp:192
uint32_t rx_input_corrections_tcp
Definition: rx_message.hpp:237
std::string ntrip_password
Password for NTRIP service.
Definition: rx_message.hpp:226
RxMessage(ROSaicNodeBase *node, Settings *settings)
Constructor of the RxMessage class.
Definition: rx_message.hpp:406
std::string rtcm_version
RTCM version for NTRIP service (if Rx does not have internet)
Definition: rx_message.hpp:234
std::string ant_serial_nr
Serial number of your particular Main antenna.
Definition: rx_message.hpp:174
septentrio_gnss_driver::PVTGeodetic PVTGeodeticMsg
Definition: typedefs.hpp:103
void wait(int seconds)
std::string rx_input_corrections_serial
Definition: rx_message.hpp:240
Derived class for parsing GSV messages.
septentrio_gnss_driver::MeasEpoch MeasEpochMsg
Definition: typedefs.hpp:97
bool ins_use_poi
INS solution reference point.
Definition: rx_message.hpp:210
std::string login_user
Username for login.
Definition: rx_message.hpp:142
ReceiverSetup last_receiversetup_
Since DiagnosticArray needs ReceiverSetup, incoming ReceiverSetup blocks need to be stored...
Definition: rx_message.hpp:723
septentrio_gnss_driver::ExtSensorMeas ExtSensorMeasMsg
Definition: typedefs.hpp:120
Declares the functions to compute and validate the CRC of a buffer.
DOP last_dop_
Since GPSFix needs DOP, incoming DOP blocks need to be stored.
Definition: rx_message.hpp:699
Struct for the SBF block "DOP".
double vsm_x
INS velocity sensor lever arm x-offset.
Definition: rx_message.hpp:198
double vsm_y
INS velocity sensor lever arm y-offset.
Definition: rx_message.hpp:200
uint64_t Timestamp
Definition: typedefs.hpp:77
septentrio_gnss_driver::AttEuler AttEulerMsg
Definition: typedefs.hpp:101
uint32_t g_cd_count
Struct for the SBF block "QualityInd".
std::string rx_serial_port
Definition: rx_message.hpp:154
bool publish_gpst
Whether or not to publish the TimeReferenceMsg message with GPST.
Definition: rx_message.hpp:286
double poi_y
INS POI offset in y-dimension.
Definition: rx_message.hpp:194
bool activate_debug_log
Set logger level to DEBUG.
Definition: rx_message.hpp:138
INSNavGeodMsg last_insnavgeod_
Since NavSatFix, GPSFix, Imu and Pose. need INSNavGeod, incoming INSNavGeod blocks need to be stored...
Definition: rx_message.hpp:676
RxIDMap rx_id_map
All instances of the RxMessage class shall have access to the map without reinitializing it...
Definition: rx_message.hpp:747
Derived class for parsing GGA messages.
double ant_lever_x
INS antenna lever arm x-offset.
Definition: rx_message.hpp:186
void newData(Timestamp recvTimestamp, const uint8_t *data, std::size_t &size)
Put new data.
Definition: rx_message.hpp:478
ChannelStatus last_channelstatus_
Since GPSFix needs ChannelStatus, incoming ChannelStatus blocks need to be stored.
Definition: rx_message.hpp:688
std::string aux1_frame_id
The frame ID of the aux1 antenna.
Definition: rx_message.hpp:316
Settings * settings_
Settings struct.
Definition: rx_message.hpp:884
uint32_t polling_period_pvt
Polling period for PVT-related SBF blocks.
Definition: rx_message.hpp:158
bool publish_insnavgeod
Whether or not to publish the INSNavGeodMsg message.
Definition: rx_message.hpp:274
bool publish_gprmc
Whether or not to publish the RMC message.
Definition: rx_message.hpp:246
bool rx_has_internet
Whether Rx has internet or not.
Definition: rx_message.hpp:232
double poi_z
INS POI offset in z-dimension.
Definition: rx_message.hpp:196
bool publish_gpgsa
Whether or not to publish the GSA message.
Definition: rx_message.hpp:248
bool use_gnss_time
Definition: rx_message.hpp:306
std::size_t count_
Number of unread bytes in the buffer.
Definition: rx_message.hpp:629
Declares lower-level string utility functions used when parsing messages.
float delta_n
Marker-to-ARP offset in the northward direction.
Definition: rx_message.hpp:164
std::string login_password
Password for login.
Definition: rx_message.hpp:144
bool publish_poscovcartesian
Definition: rx_message.hpp:260
Derived class for parsing RMC messages.
bool publish_measepoch
Whether or not to publish the MeasEpoch message.
Definition: rx_message.hpp:252
TypeOfPVTMap type_of_pvt_map
All instances of the RxMessage class shall have access to the map without reinitializing it...
Definition: rx_message.hpp:733
ROSaicNodeBase * node_
Pointer to the node.
Definition: rx_message.hpp:614
bool publish_extsensormeas
Whether or not to publish the ExtSensorMeasMsg message.
Definition: rx_message.hpp:284
double heading_offset
Attitude offset determination in longitudinal direction.
Definition: rx_message.hpp:204
std::string poi_frame_id
The frame ID used in the header of published ROS Localization message if poi is used.
Definition: rx_message.hpp:312
Settings struct.
Definition: rx_message.hpp:135
bool publish_gpgga
Whether or not to publish the GGA message.
Definition: rx_message.hpp:244
std::string mountpoint
Mountpoint for NTRIP service.
Definition: rx_message.hpp:228
std::size_t getCount()
Returns the count_ variable.
Definition: rx_message.hpp:516
bool publish_localization
Whether or not to publish the LocalizationMsg message.
Definition: rx_message.hpp:298
RxID_Enum
Definition: rx_message.hpp:348
sensor_msgs::Imu ImuMsg
Definition: typedefs.hpp:92
septentrio_gnss_driver::INSNavGeod INSNavGeodMsg
Definition: typedefs.hpp:117
std::string ant_aux1_serial_nr
Serial number of your particular Aux1 antenna.
Definition: rx_message.hpp:176
std::string septentrio_receiver_type
Septentrio receiver type, either "gnss" or "ins".
Definition: rx_message.hpp:302
Struct for the SBF block "ChannelStatus".
bool publish_pvtcartesian
Definition: rx_message.hpp:255
uint32_t baudrate
Baudrate.
Definition: rx_message.hpp:149
bool read_from_pcap
Whether or not we are reading from a PCAP file.
Definition: rx_message.hpp:326
bool publish_velcovgeodetic
Definition: rx_message.hpp:266
double theta_x
IMU orientation x-angle.
Definition: rx_message.hpp:180
bool publish_velsensorsetup
Whether or not to publish the VelSensorSetupMsg message.
Definition: rx_message.hpp:278
std::string device
Device port.
Definition: rx_message.hpp:140
bool lock_utm_zone
Wether the UTM zone of the localization is locked.
Definition: rx_message.hpp:320
std::string caster
Hostname or IP address of the NTRIP caster to connect to.
Definition: rx_message.hpp:220
VelCovGeodeticMsg last_velcovgeodetic_
Since GPSFix needs VelCovGeodetic, incoming VelCovGeodetic blocks need to be stored.
Definition: rx_message.hpp:705
septentrio_gnss_driver::PosCovGeodetic PosCovGeodeticMsg
Definition: typedefs.hpp:105
bool publish_pvtgeodetic
Whether or not to publish the PVTGeodeticMsg message.
Definition: rx_message.hpp:257
std::size_t message_size_
Helps to determine size of response message / NMEA message / SBF block.
Definition: rx_message.hpp:641
std::string ntrip_mode
Type of NTRIP connection.
Definition: rx_message.hpp:218
std::string imu_frame_id
The frame ID used in the header of published ROS Imu message.
Definition: rx_message.hpp:310
bool publish_exteventinsnavcart
Whether or not to publish the ExtEventINSNavCartMsg message.
Definition: rx_message.hpp:282
bool publish_gpsfix
Whether or not to publish the GPSFixMsg message.
Definition: rx_message.hpp:290
TypeOfPVT_Enum
Definition: rx_message.hpp:331
std::string vsm_frame_id
The frame ID of the velocity sensor.
Definition: rx_message.hpp:314
float reconnect_delay_s
Definition: rx_message.hpp:147
ReceiverStatus last_receiverstatus_
Since DiagnosticArray needs ReceiverStatus, incoming ReceiverStatus blocks need to be stored...
Definition: rx_message.hpp:711
std::string send_gga
Whether (and at which rate) or not to send GGA to the NTRIP caster.
Definition: rx_message.hpp:242
bool publish_imu
Whether or not to publish the ImuMsg message.
Definition: rx_message.hpp:296
bool publish_imusetup
Whether or not to publish the IMUSetupMsg message.
Definition: rx_message.hpp:276
double ant_lever_y
INS antenna lever arm y-offset.
Definition: rx_message.hpp:188
diagnostic_msgs::DiagnosticArray DiagnosticArrayMsg
Definition: typedefs.hpp:82
float att_std_dev
Attitude deviation mask.
Definition: rx_message.hpp:214
float pos_std_dev
Position deviation mask.
Definition: rx_message.hpp:216
std::string ant_aux1_type
Definition: rx_message.hpp:172
bool publish_exteventinsnavgeod
Whether or not to publish the ExtEventINSNavGeodMsg message.
Definition: rx_message.hpp:280
Struct for the SBF block "ReceiverStatus".
nav_msgs::Odometry LocalizationUtmMsg
Definition: typedefs.hpp:93
double vsm_z
INS velocity sensor lever arm z-offset.
Definition: rx_message.hpp:202
MeasEpochMsg last_measepoch_
Since GPSFix needs MeasEpoch (for SNRs), incoming MeasEpoch blocks need to be stored.
Definition: rx_message.hpp:694
double pitch_offset
Attitude offset determination in latitudinal direction.
Definition: rx_message.hpp:206
bool publish_atteuler
Whether or not to publish the AttEulerMsg message.
Definition: rx_message.hpp:268
std::string ntrip_version
NTRIP version for NTRIP service.
Definition: rx_message.hpp:230
std::shared_ptr< std::string > fixedUtmZone_
Fixed UTM zone.
Definition: rx_message.hpp:889
std::string datum
Datum to be used.
Definition: rx_message.hpp:156
This class is the base class for abstraction.
Definition: typedefs.hpp:160
double theta_y
IMU orientation y-angle.
Definition: rx_message.hpp:182
Can search buffer for messages, read/parse them, and so on.
Definition: rx_message.hpp:393
std::unordered_map< std::string, RxID_Enum > RxIDMap
Definition: rx_message.hpp:737
AttEulerMsg last_atteuler_
Since GPSFix etc. need AttEuler, incoming AttEuler blocks need to be stored.
Definition: rx_message.hpp:664
QualityInd last_qualityind_
Since DiagnosticArray needs QualityInd, incoming QualityInd blocks need to be stored.
Definition: rx_message.hpp:717
Struct for the SBF block "ReceiverSetup".
bool publish_gpgsv
Whether or not to publish the GSV message.
Definition: rx_message.hpp:250
uint32_t caster_port
IP port number of NTRIP caster to connect to.
Definition: rx_message.hpp:222
bool publish_diagnostics
Whether or not to publish the DiagnosticArrayMsg message.
Definition: rx_message.hpp:294
bool publish_pose
Whether or not to publish the PoseWithCovarianceStampedMsg message.
Definition: rx_message.hpp:292
std::string ins_initial_heading
For heading computation when unit is powered-cycled.
Definition: rx_message.hpp:212
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
std::unordered_map< uint16_t, TypeOfPVT_Enum > TypeOfPVTMap
Definition: rx_message.hpp:727
sensor_msgs::NavSatFix NavSatFixMsg
Definition: typedefs.hpp:89
gps_common::GPSFix GPSFixMsg
Definition: typedefs.hpp:87
bool g_read_cd
std::string ntrip_username
Username for NTRIP service.
Definition: rx_message.hpp:224
bool use_ros_axis_orientation
ROS axis orientation, body: front-left-up, geographic: ENU.
Definition: rx_message.hpp:178
geometry_msgs::PoseWithCovarianceStamped PoseWithCovarianceStampedMsg
Definition: typedefs.hpp:85
bool multi_antenna
INS multiantenna.
Definition: rx_message.hpp:208
bool publish_navsatfix
Whether or not to publish the NavSatFixMsg message.
Definition: rx_message.hpp:288
std::string frame_id
The frame ID used in the header of every published ROS message.
Definition: rx_message.hpp:308
ExtSensorMeasMsg last_extsensmeas_
Since Imu needs ExtSensorMeas, incoming ExtSensorMeas blocks need to be stored.
Definition: rx_message.hpp:682
float delta_u
Marker-to-ARP offset in the upward direction.
Definition: rx_message.hpp:166
double ant_lever_z
INS antenna lever arm z-offset.
Definition: rx_message.hpp:190
std::string ant_type
Definition: rx_message.hpp:169
bool found_
Whether or not a message has been found.
Definition: rx_message.hpp:568


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Thu Jun 23 2022 02:11:38