settings.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 #pragma once
32 
33 #include <stdint.h>
34 #include <string>
35 #include <vector>
36 
37 struct Osnma
38 {
40  std::string mode;
42  std::string ntp_server;
44  bool keep_open;
45 };
46 
47 struct RtkNtrip
48 {
50  std::string id;
52  std::string caster;
54  uint32_t caster_port;
56  std::string username;
58  std::string password;
60  std::string mountpoint;
62  std::string version;
64  bool tls;
66  std::string fingerprint;
68  std::string rtk_standard;
70  std::string send_gga;
72  bool keep_open;
73 };
74 
76 {
78  std::string id;
81  uint32_t port;
83  std::string rtk_standard;
85  std::string send_gga;
87  bool keep_open;
88 };
89 
90 struct RtkSerial
91 {
94  std::string port;
96  uint32_t baud_rate;
98  std::string rtk_standard;
100  std::string send_gga;
102  bool keep_open;
103 };
104 
105 struct Rtk
106 {
107  std::vector<RtkNtrip> ntrip;
108  std::vector<RtkIpServer> ip_server;
109  std::vector<RtkSerial> serial;
110 };
111 
112 namespace device_type {
114  {
119  };
120 } // namespace device_type
121 
123 struct Settings
124 {
128  std::string device;
132  std::string device_tcp_ip;
134  std::string device_tcp_port;
136  uint32_t udp_port;
138  std::string udp_unicast_ip;
140  std::string udp_ip_server;
142  uint32_t tcp_port;
144  std::string tcp_ip_server;
146  std::string file_name;
148  std::string login_user;
150  std::string login_password;
155  uint32_t baudrate;
157  std::string hw_flow_control;
158  // Wether to configure Rx
161  std::string datum;
167  float delta_e;
169  float delta_n;
171  float delta_u;
174  std::string ant_type;
177  std::string ant_aux1_type;
179  std::string ant_serial_nr;
181  std::string ant_aux1_serial_nr;
185  double theta_x;
187  double theta_y;
189  double theta_z;
191  double ant_lever_x;
193  double ant_lever_y;
195  double ant_lever_z;
197  double poi_x;
199  double poi_y;
201  double poi_z;
203  double vsm_x;
205  double vsm_y;
207  double vsm_z;
211  double pitch_offset;
217  std::string ins_initial_heading;
219  float att_std_dev;
221  float pos_std_dev;
304  bool insert_local_frame = false;
306  std::string local_frame_id;
316  std::string frame_id;
318  std::string imu_frame_id;
321  std::string poi_frame_id;
323  std::string vsm_frame_id;
325  std::string aux1_frame_id;
327  std::string vehicle_frame_id;
331  int32_t leap_seconds = -128;
333  bool read_from_sbf_log = false;
335  bool read_from_pcap = false;
337  std::string ins_vsm_ros_source;
339  std::vector<bool> ins_vsm_ros_config = {false, false, false};
343  std::vector<double> ins_vsm_ros_variances = {-1.0, -1.0, -1.0};
345  std::string ins_vsm_ip_server_id;
351  std::string ins_vsm_serial_port;
356 };
357 
360 {
362  bool is_ins = false;
364  bool has_heading = false;
367 };
Settings::osnma
Osnma osnma
OSNMA settings.
Definition: settings.hpp:225
Settings::publish_pose
bool publish_pose
Whether or not to publish the PoseWithCovarianceStampedMsg message.
Definition: settings.hpp:288
Settings::publish_attcoveuler
bool publish_attcoveuler
Whether or not to publish the AttCovEulerMsg message.
Definition: settings.hpp:266
device_type::TCP
@ TCP
Definition: settings.hpp:115
Settings::ins_initial_heading
std::string ins_initial_heading
For heading computation when unit is powered-cycled.
Definition: settings.hpp:217
Settings::latency_compensation
bool latency_compensation
Wether processing latency shall be compensated for in ROS timestamp.
Definition: settings.hpp:314
Settings::ins_vsm_ip_server_keep_open
bool ins_vsm_ip_server_keep_open
Wether VSM shall be kept open om shutdown.
Definition: settings.hpp:349
Osnma::keep_open
bool keep_open
Wether OSNMA shall be kept open on shutdown.
Definition: settings.hpp:44
Settings::publish_imusetup
bool publish_imusetup
Whether or not to publish the IMUSetupMsg message.
Definition: settings.hpp:272
Settings::publish_twist
bool publish_twist
Whether or not to publish the TwistWithCovarianceStampedMsg message.
Definition: settings.hpp:298
Settings::local_frame_id
std::string local_frame_id
Frame id of the local frame to be inserted.
Definition: settings.hpp:306
RtkNtrip::id
std::string id
Id of the NTRIP port.
Definition: settings.hpp:50
Settings::publish_localization
bool publish_localization
Whether or not to publish the LocalizationMsg message.
Definition: settings.hpp:294
Settings::pos_std_dev
float pos_std_dev
Position deviation mask.
Definition: settings.hpp:221
Rtk::serial
std::vector< RtkSerial > serial
Definition: settings.hpp:109
Settings::use_gnss_time
bool use_gnss_time
Definition: settings.hpp:312
device_type::DeviceType
DeviceType
Definition: settings.hpp:113
Settings::login_password
std::string login_password
Password for login.
Definition: settings.hpp:150
Settings::publish_pvtcartesian
bool publish_pvtcartesian
Definition: settings.hpp:243
Settings::udp_ip_server
std::string udp_ip_server
UDP IP server id.
Definition: settings.hpp:140
Settings::insert_local_frame
bool insert_local_frame
Wether local frame should be inserted into tf.
Definition: settings.hpp:304
Settings::publish_pvtgeodetic
bool publish_pvtgeodetic
Whether or not to publish the PVTGeodeticMsg message.
Definition: settings.hpp:245
Settings::heading_offset
double heading_offset
Attitude offset determination in longitudinal direction.
Definition: settings.hpp:209
Capabilities::has_heading
bool has_heading
Wether Rx has heading.
Definition: settings.hpp:364
Settings::publish_gpgga
bool publish_gpgga
Whether or not to publish the GGA message.
Definition: settings.hpp:227
Capabilities
Capabilities struct.
Definition: settings.hpp:359
Rtk
Definition: settings.hpp:105
RtkIpServer::keep_open
bool keep_open
Wether RTK connections shall be kept open on shutdown.
Definition: settings.hpp:87
Capabilities::has_improved_vsm_handling
bool has_improved_vsm_handling
Wether Rx has improved VSM handling.
Definition: settings.hpp:366
Settings::publish_imu
bool publish_imu
Whether or not to publish the ImuMsg message.
Definition: settings.hpp:292
Osnma::ntp_server
std::string ntp_server
Server for NTP synchronization.
Definition: settings.hpp:42
RtkSerial::baud_rate
uint32_t baud_rate
Baud rate of the serial port on which Rx receives the corrections.
Definition: settings.hpp:96
Settings::multi_antenna
bool multi_antenna
INS multiantenna.
Definition: settings.hpp:213
Settings::vsm_x
double vsm_x
INS velocity sensor lever arm x-offset.
Definition: settings.hpp:203
Settings::udp_port
uint32_t udp_port
UDP port.
Definition: settings.hpp:136
Settings::delta_n
float delta_n
Marker-to-ARP offset in the northward direction.
Definition: settings.hpp:169
Settings::polling_period_pvt
uint32_t polling_period_pvt
Polling period for PVT-related SBF blocks.
Definition: settings.hpp:163
Osnma::mode
std::string mode
OSNMA mode.
Definition: settings.hpp:40
RtkNtrip::tls
bool tls
Wether to use TLS.
Definition: settings.hpp:64
Settings::datum
std::string datum
Datum to be used.
Definition: settings.hpp:161
Settings::frame_id
std::string frame_id
The frame ID used in the header of every published ROS message.
Definition: settings.hpp:316
Settings::device_type
device_type::DeviceType device_type
Device type.
Definition: settings.hpp:130
Settings::theta_z
double theta_z
IMU orientation z-angle.
Definition: settings.hpp:189
RtkSerial::send_gga
std::string send_gga
Whether (and at which rate) or not to send GGA to the serial port.
Definition: settings.hpp:100
Settings::publish_gpst
bool publish_gpst
Whether or not to publish the TimeReferenceMsg message with GPST.
Definition: settings.hpp:282
RtkSerial::port
std::string port
Definition: settings.hpp:94
Settings::poi_frame_id
std::string poi_frame_id
Definition: settings.hpp:321
Settings::poi_y
double poi_y
INS POI offset in y-dimension.
Definition: settings.hpp:199
Settings::activate_debug_log
bool activate_debug_log
Set logger level to DEBUG.
Definition: settings.hpp:126
Settings::publish_galauthstatus
bool publish_galauthstatus
Whether or not to publish the GALAuthStatus message and diagnostics.
Definition: settings.hpp:240
Settings::publish_velcovcartesian
bool publish_velcovcartesian
Definition: settings.hpp:259
Settings::publish_aimplusstatus
bool publish_aimplusstatus
Definition: settings.hpp:238
Settings::poi_x
double poi_x
INS POI offset in x-dimension.
Definition: settings.hpp:197
Settings::ins_vsm_ros_variances_by_parameter
bool ins_vsm_ros_variances_by_parameter
Whether or not to use variance defined by ROS parameter.
Definition: settings.hpp:341
Settings::tcp_ip_server
std::string tcp_ip_server
TCP IP server id.
Definition: settings.hpp:144
Settings::theta_x
double theta_x
IMU orientation x-angle.
Definition: settings.hpp:185
Settings::publish_velsensorsetup
bool publish_velsensorsetup
Whether or not to publish the VelSensorSetupMsg message.
Definition: settings.hpp:274
Settings::theta_y
double theta_y
IMU orientation y-angle.
Definition: settings.hpp:187
Settings::ant_aux1_serial_nr
std::string ant_aux1_serial_nr
Serial number of your particular Aux1 antenna.
Definition: settings.hpp:181
RtkNtrip::send_gga
std::string send_gga
Whether (and at which rate) or not to send GGA to the NTRIP caster.
Definition: settings.hpp:70
RtkNtrip::fingerprint
std::string fingerprint
Self-signed certificate fingerprint.
Definition: settings.hpp:66
Settings::publish_exteventinsnavcart
bool publish_exteventinsnavcart
Whether or not to publish the ExtEventINSNavCartMsg message.
Definition: settings.hpp:278
Settings::publish_gpsfix
bool publish_gpsfix
Whether or not to publish the GpsFixMsg message.
Definition: settings.hpp:286
Settings::configure_rx
bool configure_rx
Definition: settings.hpp:159
Settings::publish_gpgsa
bool publish_gpgsa
Whether or not to publish the GSA message.
Definition: settings.hpp:231
Settings::vsm_frame_id
std::string vsm_frame_id
The frame ID of the velocity sensor.
Definition: settings.hpp:323
Settings::baudrate
uint32_t baudrate
Baudrate.
Definition: settings.hpp:155
Settings::publish_velcovgeodetic
bool publish_velcovgeodetic
Definition: settings.hpp:262
RtkNtrip::caster
std::string caster
Hostname or IP address of the NTRIP caster to connect to.
Definition: settings.hpp:52
Settings::tcp_port
uint32_t tcp_port
TCP port.
Definition: settings.hpp:142
Settings::publish_poscovgeodetic
bool publish_poscovgeodetic
Definition: settings.hpp:256
Settings::publish_tf_ecef
bool publish_tf_ecef
Whether or not to publish the tf of the localization.
Definition: settings.hpp:302
Settings::vsm_y
double vsm_y
INS velocity sensor lever arm y-offset.
Definition: settings.hpp:205
Settings::publish_basevectorcart
bool publish_basevectorcart
Definition: settings.hpp:248
RtkNtrip
Definition: settings.hpp:47
Rtk::ntrip
std::vector< RtkNtrip > ntrip
Definition: settings.hpp:107
device_type::SBF_FILE
@ SBF_FILE
Definition: settings.hpp:117
Settings::ins_vsm_ros_config
std::vector< bool > ins_vsm_ros_config
Whether or not to use individual elements of 3D velocity (v_x, v_y, v_z)
Definition: settings.hpp:339
RtkSerial
Definition: settings.hpp:90
RtkSerial::keep_open
bool keep_open
Wether RTK connections shall be kept open on shutdown.
Definition: settings.hpp:102
RtkNtrip::caster_port
uint32_t caster_port
IP port number of NTRIP caster to connect to.
Definition: settings.hpp:54
Settings::vsm_z
double vsm_z
INS velocity sensor lever arm z-offset.
Definition: settings.hpp:207
Settings::use_ros_axis_orientation
bool use_ros_axis_orientation
ROS axis orientation, body: front-left-up, geographic: ENU.
Definition: settings.hpp:183
Settings::pitch_offset
double pitch_offset
Attitude offset determination in latitudinal direction.
Definition: settings.hpp:211
Settings::ant_aux1_type
std::string ant_aux1_type
Definition: settings.hpp:177
Settings::publish_localization_ecef
bool publish_localization_ecef
Whether or not to publish the LocalizationMsg message.
Definition: settings.hpp:296
Settings::delta_u
float delta_u
Marker-to-ARP offset in the upward direction.
Definition: settings.hpp:171
Settings::file_name
std::string file_name
Filename.
Definition: settings.hpp:146
Settings::ins_use_poi
bool ins_use_poi
INS solution reference point.
Definition: settings.hpp:215
Settings::ant_serial_nr
std::string ant_serial_nr
Serial number of your particular Main antenna.
Definition: settings.hpp:179
Settings::ins_vsm_ip_server_port
uint32_t ins_vsm_ip_server_port
VSM tcp port.
Definition: settings.hpp:347
Settings::ant_type
std::string ant_type
Definition: settings.hpp:174
device_type
Definition: settings.hpp:112
Settings::publish_atteuler
bool publish_atteuler
Whether or not to publish the AttEulerMsg message.
Definition: settings.hpp:264
Settings::login_user
std::string login_user
Username for login.
Definition: settings.hpp:148
Settings::lock_utm_zone
bool lock_utm_zone
Wether the UTM zone of the localization is locked.
Definition: settings.hpp:329
Settings::publish_basevectorgeod
bool publish_basevectorgeod
Whether or not to publish the BaseVectorGeodMsg message.
Definition: settings.hpp:250
Settings::publish_diagnostics
bool publish_diagnostics
Whether or not to publish the DiagnosticArrayMsg message.
Definition: settings.hpp:290
Settings::imu_frame_id
std::string imu_frame_id
The frame ID used in the header of published ROS Imu message.
Definition: settings.hpp:318
Settings::polling_period_rest
uint32_t polling_period_rest
Polling period for all other SBF blocks and NMEA messages.
Definition: settings.hpp:165
Settings::device_tcp_port
std::string device_tcp_port
TCP port.
Definition: settings.hpp:134
RtkNtrip::version
std::string version
NTRIP version for NTRIP service.
Definition: settings.hpp:62
Rtk::ip_server
std::vector< RtkIpServer > ip_server
Definition: settings.hpp:108
device_type::SERIAL
@ SERIAL
Definition: settings.hpp:116
RtkNtrip::rtk_standard
std::string rtk_standard
RTCM version for correction data.
Definition: settings.hpp:68
Settings::poi_z
double poi_z
INS POI offset in z-dimension.
Definition: settings.hpp:201
Settings::ins_vsm_serial_port
std::string ins_vsm_serial_port
VSM serial port.
Definition: settings.hpp:351
RtkIpServer::port
uint32_t port
Definition: settings.hpp:81
Settings
Settings struct.
Definition: settings.hpp:123
RtkNtrip::username
std::string username
Username for NTRIP service.
Definition: settings.hpp:56
Settings::publish_poscovcartesian
bool publish_poscovcartesian
Definition: settings.hpp:253
RtkSerial::rtk_standard
std::string rtk_standard
RTCM version for correction data.
Definition: settings.hpp:98
Settings::publish_insnavcart
bool publish_insnavcart
Whether or not to publish the INSNavCartMsg message.
Definition: settings.hpp:268
Settings::delta_e
float delta_e
Marker-to-ARP offset in the eastward direction.
Definition: settings.hpp:167
device_type::PCAP_FILE
@ PCAP_FILE
Definition: settings.hpp:118
Settings::read_from_sbf_log
bool read_from_sbf_log
Whether or not we are reading from an SBF file.
Definition: settings.hpp:333
Settings::hw_flow_control
std::string hw_flow_control
HW flow control.
Definition: settings.hpp:157
Osnma
Definition: settings.hpp:37
RtkIpServer::rtk_standard
std::string rtk_standard
RTCM version for correction data.
Definition: settings.hpp:83
Settings::device_tcp_ip
std::string device_tcp_ip
TCP IP.
Definition: settings.hpp:132
Settings::ant_lever_z
double ant_lever_z
INS antenna lever arm z-offset.
Definition: settings.hpp:195
Settings::vehicle_frame_id
std::string vehicle_frame_id
The frame ID of the vehicle frame.
Definition: settings.hpp:327
Settings::leap_seconds
int32_t leap_seconds
The number of leap seconds that have been inserted into the UTC time.
Definition: settings.hpp:331
Settings::publish_gprmc
bool publish_gprmc
Whether or not to publish the RMC message.
Definition: settings.hpp:229
Settings::ins_vsm_ros_source
std::string ins_vsm_ros_source
VSM source for INS.
Definition: settings.hpp:337
Capabilities::is_ins
bool is_ins
Wether Rx is INS.
Definition: settings.hpp:362
Settings::ins_vsm_serial_baud_rate
uint32_t ins_vsm_serial_baud_rate
VSM serial baud rate.
Definition: settings.hpp:353
RtkNtrip::keep_open
bool keep_open
Wether RTK connections shall be kept open on shutdown.
Definition: settings.hpp:72
Settings::aux1_frame_id
std::string aux1_frame_id
The frame ID of the aux1 antenna.
Definition: settings.hpp:325
Settings::publish_navsatfix
bool publish_navsatfix
Whether or not to publish the NavSatFixMsg message.
Definition: settings.hpp:284
Settings::reconnect_delay_s
float reconnect_delay_s
Definition: settings.hpp:153
RtkIpServer
Definition: settings.hpp:75
Settings::publish_tf
bool publish_tf
Whether or not to publish the tf of the localization.
Definition: settings.hpp:300
Settings::udp_unicast_ip
std::string udp_unicast_ip
UDP unicast destination ip.
Definition: settings.hpp:138
Settings::ins_vsm_ros_variances
std::vector< double > ins_vsm_ros_variances
Variances of the 3D velocity (var_x, var_y, var_z)
Definition: settings.hpp:343
Settings::att_std_dev
float att_std_dev
Attitude deviation mask.
Definition: settings.hpp:219
Settings::publish_measepoch
bool publish_measepoch
Whether or not to publish the MeasEpoch message.
Definition: settings.hpp:235
Settings::publish_exteventinsnavgeod
bool publish_exteventinsnavgeod
Whether or not to publish the ExtEventINSNavGeodMsg message.
Definition: settings.hpp:276
Settings::ins_vsm_ip_server_id
std::string ins_vsm_ip_server_id
VSM IP server id.
Definition: settings.hpp:345
RtkIpServer::id
std::string id
The IP server id.
Definition: settings.hpp:78
Settings::ant_lever_x
double ant_lever_x
INS antenna lever arm x-offset.
Definition: settings.hpp:191
Settings::publish_extsensormeas
bool publish_extsensormeas
Whether or not to publish the ExtSensorMeasMsg message.
Definition: settings.hpp:280
RtkNtrip::mountpoint
std::string mountpoint
Mountpoint for NTRIP service.
Definition: settings.hpp:60
Settings::device
std::string device
Device.
Definition: settings.hpp:128
Settings::publish_insnavgeod
bool publish_insnavgeod
Whether or not to publish the INSNavGeodMsg message.
Definition: settings.hpp:270
Settings::rtk
Rtk rtk
RTK corrections settings.
Definition: settings.hpp:223
RtkNtrip::password
std::string password
Password for NTRIP service.
Definition: settings.hpp:58
Settings::septentrio_receiver_type
std::string septentrio_receiver_type
Septentrio receiver type, either "gnss" or "ins".
Definition: settings.hpp:308
Settings::read_from_pcap
bool read_from_pcap
Whether or not we are reading from a PCAP file.
Definition: settings.hpp:335
Settings::ins_vsm_serial_keep_open
bool ins_vsm_serial_keep_open
Wether VSM shall be kept open om shutdown.
Definition: settings.hpp:355
Settings::publish_gpgsv
bool publish_gpgsv
Whether or not to publish the GSV message.
Definition: settings.hpp:233
Settings::ant_lever_y
double ant_lever_y
INS antenna lever arm y-offset.
Definition: settings.hpp:193
RtkIpServer::send_gga
std::string send_gga
Whether (and at which rate) or not to send GGA to the NTRIP caster.
Definition: settings.hpp:85


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Wed Nov 22 2023 04:04:27