settings.h
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 RtkNtrip
38 {
40  std::string id;
42  std::string caster;
44  uint32_t caster_port;
46  std::string username;
48  std::string password;
50  std::string mountpoint;
52  std::string version;
54  bool tls;
56  std::string fingerprint;
58  std::string rtk_standard;
60  std::string send_gga;
62  bool keep_open;
63 };
64 
66 {
68  std::string id;
71  uint32_t port;
73  std::string rtk_standard;
75  std::string send_gga;
77  bool keep_open;
78 };
79 
80 struct RtkSerial
81 {
84  std::string port;
86  uint32_t baud_rate;
88  std::string rtk_standard;
90  std::string send_gga;
92  bool keep_open;
93 };
94 
96 {
97  std::vector<RtkNtrip> ntrip;
98  std::vector<RtkIpServer> ip_server;
99  std::vector<RtkSerial> serial;
100 };
101 
103 struct Settings
104 {
108  std::string device;
110  std::string login_user;
112  std::string login_password;
117  uint32_t baudrate;
119  std::string hw_flow_control;
122  std::string rx_serial_port;
124  std::string datum;
130  float delta_e;
132  float delta_n;
134  float delta_u;
137  std::string ant_type;
140  std::string ant_aux1_type;
142  std::string ant_serial_nr;
144  std::string ant_aux1_serial_nr;
148  double theta_x;
150  double theta_y;
152  double theta_z;
154  double ant_lever_x;
156  double ant_lever_y;
158  double ant_lever_z;
160  double poi_x;
162  double poi_y;
164  double poi_z;
166  double vsm_x;
168  double vsm_y;
170  double vsm_z;
174  double pitch_offset;
180  std::string ins_initial_heading;
182  float att_std_dev;
184  float pos_std_dev;
253  bool insert_local_frame = false;
255  std::string local_frame_id;
259  bool ins_in_gnss_mode = false;
265  std::string frame_id;
267  std::string imu_frame_id;
270  std::string poi_frame_id;
272  std::string vsm_frame_id;
274  std::string aux1_frame_id;
276  std::string vehicle_frame_id;
280  int32_t leap_seconds;
282  bool read_from_sbf_log = false;
284  bool read_from_pcap = false;
286  std::string ins_vsm_ros_source;
288  std::vector<bool> ins_vsm_ros_config = {false, false, false};
290  bool ins_vsm_ros_variances_by_parameter = false;
292  std::vector<double> ins_vsm_ros_variances = {-1.0, -1.0, -1.0};
294  std::string ins_vsm_ip_server_id;
300  std::string ins_vsm_serial_port;
305 };
double theta_z
IMU orientation z-angle.
Definition: settings.h:152
uint32_t polling_period_rest
Polling period for all other SBF blocks and NMEA messages.
Definition: settings.h:128
std::string vehicle_frame_id
The frame ID of the vehicle frame.
Definition: settings.h:276
bool keep_open
Wether RTK connections shall be kept open on shutdown.
Definition: settings.h:62
uint32_t ins_vsm_serial_baud_rate
VSM serial baud rate.
Definition: settings.h:302
uint32_t ins_vsm_ip_server_port
VSM tcp port.
Definition: settings.h:296
std::string id
Id of the NTRIP port.
Definition: settings.h:40
std::string send_gga
Whether (and at which rate) or not to send GGA to the NTRIP caster.
Definition: settings.h:60
bool tls
Wether to use TLS.
Definition: settings.h:54
bool publish_basevectorgeod
Whether or not to publish the BaseVectorGeodMsg message.
Definition: settings.h:206
bool publish_insnavcart
Whether or not to publish the INSNavCartMsg message.
Definition: settings.h:221
bool publish_attcoveuler
Whether or not to publish the AttCovEulerMsg message.
Definition: settings.h:219
float delta_e
Marker-to-ARP offset in the eastward direction.
Definition: settings.h:130
bool publish_tf
Whether or not to publish the tf of the localization.
Definition: settings.h:251
std::string ins_vsm_ip_server_id
VSM IP server id.
Definition: settings.h:294
std::string hw_flow_control
HW flow control.
Definition: settings.h:119
bool publish_poscovgeodetic
Definition: settings.h:212
std::string ins_vsm_serial_port
VSM serial port.
Definition: settings.h:300
double poi_x
INS POI offset in x-dimension.
Definition: settings.h:160
std::string ant_serial_nr
Serial number of your particular Main antenna.
Definition: settings.h:142
std::string rtk_standard
RTCM version for correction data.
Definition: settings.h:58
RtkSettings rtk_settings
RTK corrections settings.
Definition: settings.h:186
bool ins_use_poi
INS solution reference point.
Definition: settings.h:178
std::string send_gga
Whether (and at which rate) or not to send GGA to the NTRIP caster.
Definition: settings.h:75
std::string id
The IP server id.
Definition: settings.h:68
std::string login_user
Username for login.
Definition: settings.h:110
std::vector< RtkNtrip > ntrip
Definition: settings.h:97
std::string ins_vsm_ros_source
VSM source for INS.
Definition: settings.h:286
std::string port
Definition: settings.h:84
double vsm_x
INS velocity sensor lever arm x-offset.
Definition: settings.h:166
double vsm_y
INS velocity sensor lever arm y-offset.
Definition: settings.h:168
uint32_t baud_rate
Baud rate of the serial port on which Rx receives the corrections.
Definition: settings.h:86
std::string fingerprint
Self-signed certificate fingerprint.
Definition: settings.h:56
bool publish_twist
Whether or not to publish the TwistWithCovarianceStampedMsg message.
Definition: settings.h:249
std::string rx_serial_port
Definition: settings.h:122
bool publish_gpst
Whether or not to publish the TimeReferenceMsg message with GPST.
Definition: settings.h:235
double poi_y
INS POI offset in y-dimension.
Definition: settings.h:162
bool keep_open
Wether RTK connections shall be kept open on shutdown.
Definition: settings.h:92
bool activate_debug_log
Set logger level to DEBUG.
Definition: settings.h:106
double ant_lever_x
INS antenna lever arm x-offset.
Definition: settings.h:154
std::string aux1_frame_id
The frame ID of the aux1 antenna.
Definition: settings.h:274
std::string mountpoint
Mountpoint for NTRIP service.
Definition: settings.h:50
uint32_t polling_period_pvt
Polling period for PVT-related SBF blocks.
Definition: settings.h:126
bool publish_insnavgeod
Whether or not to publish the INSNavGeodMsg message.
Definition: settings.h:223
std::string password
Password for NTRIP service.
Definition: settings.h:48
bool publish_gprmc
Whether or not to publish the RMC message.
Definition: settings.h:190
double poi_z
INS POI offset in z-dimension.
Definition: settings.h:164
bool publish_gpgsa
Whether or not to publish the GSA message.
Definition: settings.h:192
bool use_gnss_time
Definition: settings.h:263
bool ins_vsm_serial_keep_open
Wether VSM shall be kept open om shutdown.
Definition: settings.h:304
float delta_n
Marker-to-ARP offset in the northward direction.
Definition: settings.h:132
std::string login_password
Password for login.
Definition: settings.h:112
std::string send_gga
Whether (and at which rate) or not to send GGA to the serial port.
Definition: settings.h:90
bool publish_poscovcartesian
Definition: settings.h:209
bool publish_measepoch
Whether or not to publish the MeasEpoch message.
Definition: settings.h:196
bool publish_basevectorcart
Definition: settings.h:204
std::string rtk_standard
RTCM version for correction data.
Definition: settings.h:73
bool publish_extsensormeas
Whether or not to publish the ExtSensorMeasMsg message.
Definition: settings.h:233
double heading_offset
Attitude offset determination in longitudinal direction.
Definition: settings.h:172
std::string poi_frame_id
Definition: settings.h:270
Settings struct.
Definition: settings.h:103
bool publish_gpgga
Whether or not to publish the GGA message.
Definition: settings.h:188
bool publish_localization
Whether or not to publish the LocalizationMsg message.
Definition: settings.h:247
int32_t leap_seconds
The number of leap seconds that have been inserted into the UTC time.
Definition: settings.h:280
std::string ant_aux1_serial_nr
Serial number of your particular Aux1 antenna.
Definition: settings.h:144
std::string septentrio_receiver_type
Septentrio receiver type, either "gnss" or "ins".
Definition: settings.h:257
bool publish_pvtcartesian
Definition: settings.h:199
uint32_t baudrate
Baudrate.
Definition: settings.h:117
bool publish_velcovgeodetic
Definition: settings.h:215
double theta_x
IMU orientation x-angle.
Definition: settings.h:148
bool publish_velsensorsetup
Whether or not to publish the VelSensorSetupMsg message.
Definition: settings.h:227
std::string device
Device port.
Definition: settings.h:108
bool lock_utm_zone
Wether the UTM zone of the localization is locked.
Definition: settings.h:278
bool publish_pvtgeodetic
Whether or not to publish the PVTGeodeticMsg message.
Definition: settings.h:201
std::string imu_frame_id
The frame ID used in the header of published ROS Imu message.
Definition: settings.h:267
bool publish_exteventinsnavcart
Whether or not to publish the ExtEventINSNavCartMsg message.
Definition: settings.h:231
bool publish_gpsfix
Whether or not to publish the GPSFixMsg message.
Definition: settings.h:239
std::string vsm_frame_id
The frame ID of the velocity sensor.
Definition: settings.h:272
float reconnect_delay_s
Definition: settings.h:115
bool ins_vsm_ip_server_keep_open
Wether VSM shall be kept open om shutdown.
Definition: settings.h:298
bool publish_imu
Whether or not to publish the ImuMsg message.
Definition: settings.h:245
bool publish_imusetup
Whether or not to publish the IMUSetupMsg message.
Definition: settings.h:225
double ant_lever_y
INS antenna lever arm y-offset.
Definition: settings.h:156
bool keep_open
Wether RTK connections shall be kept open on shutdown.
Definition: settings.h:77
float att_std_dev
Attitude deviation mask.
Definition: settings.h:182
float pos_std_dev
Position deviation mask.
Definition: settings.h:184
std::string ant_aux1_type
Definition: settings.h:140
bool publish_exteventinsnavgeod
Whether or not to publish the ExtEventINSNavGeodMsg message.
Definition: settings.h:229
std::vector< RtkSerial > serial
Definition: settings.h:99
uint32_t caster_port
IP port number of NTRIP caster to connect to.
Definition: settings.h:44
double vsm_z
INS velocity sensor lever arm z-offset.
Definition: settings.h:170
double pitch_offset
Attitude offset determination in latitudinal direction.
Definition: settings.h:174
bool publish_atteuler
Whether or not to publish the AttEulerMsg message.
Definition: settings.h:217
std::string datum
Datum to be used.
Definition: settings.h:124
double theta_y
IMU orientation y-angle.
Definition: settings.h:150
std::string rtk_standard
RTCM version for correction data.
Definition: settings.h:88
bool publish_gpgsv
Whether or not to publish the GSV message.
Definition: settings.h:194
bool publish_diagnostics
Whether or not to publish the DiagnosticArrayMsg message.
Definition: settings.h:243
std::vector< RtkIpServer > ip_server
Definition: settings.h:98
bool publish_pose
Whether or not to publish the PoseWithCovarianceStampedMsg message.
Definition: settings.h:241
uint32_t port
Definition: settings.h:71
std::string ins_initial_heading
For heading computation when unit is powered-cycled.
Definition: settings.h:180
std::string version
NTRIP version for NTRIP service.
Definition: settings.h:52
bool use_ros_axis_orientation
ROS axis orientation, body: front-left-up, geographic: ENU.
Definition: settings.h:146
bool multi_antenna
INS multiantenna.
Definition: settings.h:176
std::string local_frame_id
Frame id of the local frame to be inserted.
Definition: settings.h:255
std::string username
Username for NTRIP service.
Definition: settings.h:46
bool publish_navsatfix
Whether or not to publish the NavSatFixMsg message.
Definition: settings.h:237
std::string frame_id
The frame ID used in the header of every published ROS message.
Definition: settings.h:265
float delta_u
Marker-to-ARP offset in the upward direction.
Definition: settings.h:134
std::string caster
Hostname or IP address of the NTRIP caster to connect to.
Definition: settings.h:42
double ant_lever_z
INS antenna lever arm z-offset.
Definition: settings.h:158
std::string ant_type
Definition: settings.h:137


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Sat Mar 11 2023 03:12:56