rosaic_node.cpp
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 // Eigen include
32 #include <Eigen/Geometry>
33 
35 
43  IO_(this, &settings_)
44 {
45  param("activate_debug_log", settings_.activate_debug_log, false);
47  {
50  ros::console::levels::Debug)) // debug is lowest level, shows everything
52  }
53 
54  this->log(LogLevel::DEBUG, "Called ROSaicNode() constructor..");
55 
57 
58  // Parameters must be set before initializing IO
59  if (!getROSParams())
60  return;
61 
62  // Initializes Connection
63  IO_.initializeIO();
64 
65  // Subscribes to all requested Rx messages by adding entries to the C++ multimap
66  // storing the callback handlers and publishes ROS messages
68 
69  // Sends commands to the Rx regarding which SBF/NMEA messages it should output
70  // and sets all its necessary corrections-related parameters
72  {
73  IO_.configureRx();
74  }
75 
76  this->log(LogLevel::DEBUG, "Leaving ROSaicNode() constructor..");
77 }
78 
80 {
81  param("use_gnss_time", settings_.use_gnss_time, true);
82  param("frame_id", settings_.frame_id, (std::string) "gnss");
83  param("imu_frame_id", settings_.imu_frame_id, (std::string) "imu");
84  param("poi_frame_id", settings_.poi_frame_id, (std::string) "base_link");
85  param("vsm_frame_id", settings_.vsm_frame_id, (std::string) "vsm");
86  param("aux1_frame_id", settings_.aux1_frame_id, (std::string) "aux1");
88  param("lock_utm_zone", settings_.lock_utm_zone, true);
89  getUint32Param("leap_seconds", settings_.leap_seconds,
90  static_cast<uint32_t>(18));
91 
92  // Communication parameters
93  param("device", settings_.device, std::string("/dev/ttyACM0"));
94  getUint32Param("serial/baudrate", settings_.baudrate, static_cast<uint32_t>(921600));
95  param("serial/hw_flow_control", settings_.hw_flow_control, std::string("off"));
96  param("serial/rx_serial_port", settings_.rx_serial_port, std::string("USB1"));
97  param("login/user", settings_.login_user, std::string(""));
98  param("login/password", settings_.login_password, std::string(""));
99  settings_.reconnect_delay_s = 2.0f; // Removed from ROS parameter list.
100  param("receiver_type", settings_.septentrio_receiver_type, std::string("gnss"));
101  if (!((settings_.septentrio_receiver_type == "gnss") || (settings_.septentrio_receiver_type == "ins")))
102  {
103  this->log(LogLevel::FATAL, "Unkown septentrio_receiver_type " + settings_.septentrio_receiver_type + " use either gnss or ins.");
104  return false;
105  }
106 
107  // Polling period parameters
108  getUint32Param("polling_period/pvt", settings_.polling_period_pvt,
109  static_cast<uint32_t>(1000));
116  {
117  this->log(LogLevel::FATAL,
118  "Please specify a valid polling period for PVT-related SBF blocks and NMEA messages.");
119  return false;
120  }
121  getUint32Param("polling_period/rest", settings_.polling_period_rest,
122  static_cast<uint32_t>(1000));
129  {
130  this->log(LogLevel::FATAL,
131  "Please specify a valid polling period for PVT-unrelated SBF blocks and NMEA messages.");
132  return false;
133  }
134 
135  // multi_antenna param
136  param("multi_antenna", settings_.multi_antenna, false);
137 
138  // Publishing parameters
139  param("publish/gpst", settings_.publish_gpst, false);
140  param("publish/navsatfix", settings_.publish_navsatfix, true);
141  param("publish/gpsfix", settings_.publish_gpsfix, false);
142  param("publish/pose", settings_.publish_pose, false);
143  param("publish/diagnostics", settings_.publish_diagnostics, false);
144  param("publish/gpgga", settings_.publish_gpgga, false);
145  param("publish/gprmc", settings_.publish_gprmc, false);
146  param("publish/gpgsa", settings_.publish_gpgsa, false);
147  param("publish/gpgsv", settings_.publish_gpgsv, false);
148  param("publish/measepoch", settings_.publish_measepoch, false);
149  param("publish/pvtcartesian", settings_.publish_pvtcartesian, false);
150  param("publish/pvtgeodetic", settings_.publish_pvtgeodetic, (settings_.septentrio_receiver_type == "gnss"));
151  param("publish/poscovcartesian", settings_.publish_poscovcartesian, false);
152  param("publish/poscovgeodetic", settings_.publish_poscovgeodetic, (settings_.septentrio_receiver_type == "gnss"));
153  param("publish/velcovgeodetic", settings_.publish_velcovgeodetic, (settings_.septentrio_receiver_type == "gnss"));
156  param("publish/insnavcart", settings_.publish_insnavcart, false);
157  param("publish/insnavgeod", settings_.publish_insnavgeod, (settings_.septentrio_receiver_type == "ins"));
158  param("publish/imusetup", settings_.publish_imusetup, false);
159  param("publish/velsensorsetup", settings_.publish_velsensorsetup, false);
160  param("publish/exteventinsnavgeod", settings_.publish_exteventinsnavgeod, false);
161  param("publish/exteventinsnavcart", settings_.publish_exteventinsnavcart, false);
162  param("publish/extsensormeas", settings_.publish_extsensormeas, false);
163  param("publish/imu", settings_.publish_imu, false);
164  param("publish/localization", settings_.publish_localization, false);
165  param("publish/tf", settings_.publish_tf, false);
166 
167  // Datum and marker-to-ARP offset
168  param("datum", settings_.datum, std::string("ETRS89"));
169  param("ant_type", settings_.ant_type, std::string("Unknown"));
170  param("ant_aux1_type", settings_.ant_aux1_type, std::string("Unknown"));
171  param("ant_serial_nr", settings_.ant_serial_nr, std::string());
172  if (settings_.ant_serial_nr.empty())
173  {
174  uint32_t sn_tmp;
175  if (getUint32Param("ant_serial_nr", sn_tmp, static_cast<uint32_t>(0)))
176  settings_.ant_serial_nr = std::to_string(sn_tmp);
177  else
178  settings_.ant_serial_nr = "Unknown";
179  }
180  param("ant_aux1_serial_nr", settings_.ant_aux1_serial_nr, std::string());
181  if (settings_.ant_aux1_serial_nr.empty())
182  {
183  uint32_t sn_tmp;
184  if (getUint32Param("ant_aux1_serial_nr", sn_tmp, static_cast<uint32_t>(0)))
185  settings_.ant_aux1_serial_nr = std::to_string(sn_tmp);
186  else
187  settings_.ant_aux1_serial_nr = "Unknown";
188  }
189  param("poi_to_arp/delta_e", settings_.delta_e, 0.0f);
190  param("poi_to_arp/delta_n", settings_.delta_n, 0.0f);
191  param("poi_to_arp/delta_u", settings_.delta_u, 0.0f);
192 
193  param("use_ros_axis_orientation", settings_.use_ros_axis_orientation, true);
194 
195  // INS Spatial Configuration
196  bool getConfigFromTf;
197  param("get_spatial_config_from_tf", getConfigFromTf, false);
198  if (getConfigFromTf)
199  {
200  if (settings_.septentrio_receiver_type == "ins")
201  {
202  TransformStampedMsg T_imu_vehicle;
204  TransformStampedMsg T_poi_imu;
206  TransformStampedMsg T_vsm_imu;
208  TransformStampedMsg T_ant_imu;
210 
211  // IMU orientation parameter
212  double roll, pitch, yaw;
213  getRPY(T_imu_vehicle.transform.rotation, roll, pitch, yaw);
217  // INS antenna lever arm offset parameter
218  settings_.ant_lever_x = T_ant_imu.transform.translation.x;
219  settings_.ant_lever_y = T_ant_imu.transform.translation.y;
220  settings_.ant_lever_z = T_ant_imu.transform.translation.z;
221  // INS POI ofset paramter
222  settings_.poi_x = T_poi_imu.transform.translation.x;
223  settings_.poi_y = T_poi_imu.transform.translation.y;
224  settings_.poi_z = T_poi_imu.transform.translation.z;
225  // INS velocity sensor lever arm offset parameter
226  settings_.vsm_x = T_vsm_imu.transform.translation.x;
227  settings_.vsm_y = T_vsm_imu.transform.translation.y;
228  settings_.vsm_z = T_vsm_imu.transform.translation.z;
229 
231  {
232  TransformStampedMsg T_aux1_imu;
234  // Antenna Attitude Determination parameter
235  double dy = T_aux1_imu.transform.translation.y - T_ant_imu.transform.translation.y;
236  double dx = T_aux1_imu.transform.translation.x - T_ant_imu.transform.translation.x;
238  double dz = T_aux1_imu.transform.translation.z - T_ant_imu.transform.translation.z;
239  double dr = std::sqrt(parsing_utilities::square(dx) + parsing_utilities::square(dy));
240  settings_.pitch_offset = parsing_utilities::rad2deg(std::atan2(-dz, dr));
241  }
242  }
244  {
245  TransformStampedMsg T_ant_vehicle;
247  TransformStampedMsg T_aux1_vehicle;
249 
250  // Antenna Attitude Determination parameter
251  double dy = T_aux1_vehicle.transform.translation.y - T_ant_vehicle.transform.translation.y;
252  double dx = T_aux1_vehicle.transform.translation.x - T_ant_vehicle.transform.translation.x;
254  double dz = T_aux1_vehicle.transform.translation.z - T_ant_vehicle.transform.translation.z;
255  double dr = std::sqrt(parsing_utilities::square(dx) + parsing_utilities::square(dy));
256  settings_.pitch_offset = parsing_utilities::rad2deg(std::atan2(-dz, dr));
257  }
258  }
259  else
260  {
261  // IMU orientation parameter
262  param("ins_spatial_config/imu_orientation/theta_x", settings_.theta_x, 0.0);
263  param("ins_spatial_config/imu_orientation/theta_y", settings_.theta_y, 0.0);
264  param("ins_spatial_config/imu_orientation/theta_z", settings_.theta_z, 0.0);
265  // INS antenna lever arm offset parameter
266  param("ins_spatial_config/ant_lever_arm/x", settings_.ant_lever_x, 0.0);
267  param("ins_spatial_config/ant_lever_arm/y", settings_.ant_lever_y, 0.0);
268  param("ins_spatial_config/ant_lever_arm/z", settings_.ant_lever_z, 0.0);
269  // INS POI ofset paramter
270  param("ins_spatial_config/poi_lever_arm/delta_x", settings_.poi_x, 0.0);
271  param("ins_spatial_config/poi_lever_arm/delta_y", settings_.poi_y, 0.0);
272  param("ins_spatial_config/poi_lever_arm/delta_z", settings_.poi_z, 0.0);
273  // INS velocity sensor lever arm offset parameter
274  param("ins_spatial_config/vel_sensor_lever_arm/vsm_x", settings_.vsm_x, 0.0);
275  param("ins_spatial_config/vel_sensor_lever_arm/vsm_y", settings_.vsm_y, 0.0);
276  param("ins_spatial_config/vel_sensor_lever_arm/vsm_z", settings_.vsm_z, 0.0);
277  // Antenna Attitude Determination parameter
278  param("att_offset/heading", settings_.heading_offset, 0.0);
279  param("att_offset/pitch", settings_.pitch_offset, 0.0);
280  }
281 
283  {
285  settings_.theta_y *= -1.0;
286  settings_.theta_z *= -1.0;
287  settings_.ant_lever_y *= -1.0;
288  settings_.ant_lever_z *= -1.0;
289  settings_.poi_y *= -1.0;
290  settings_.poi_z *= -1.0;
291  settings_.vsm_y *= -1.0;
292  settings_.vsm_z *= -1.0;
293  settings_.heading_offset *= -1.0;
294  settings_.pitch_offset *= -1.0;
295  }
296 
297  if (std::abs(settings_.heading_offset) > std::numeric_limits<double>::epsilon())
298  {
300  {
301  this->log(LogLevel::WARN , "Pitch angle output by topic /atteuler is a tilt angle rotated by " +
302  std::to_string(settings_.heading_offset) + ".");
303  }
305  {
306  this->log(LogLevel::WARN , "Pitch angle output by topic /pose is a tilt angle rotated by " +
307  std::to_string(settings_.heading_offset) + ".");
308  }
309  }
310 
311  this->log(LogLevel::DEBUG , "IMU roll offset: "+ std::to_string(settings_.theta_x));
312  this->log(LogLevel::DEBUG , "IMU pitch offset: "+ std::to_string(settings_.theta_y));
313  this->log(LogLevel::DEBUG , "IMU yaw offset: "+ std::to_string(settings_.theta_z));
314  this->log(LogLevel::DEBUG , "Ant heading offset: " + std::to_string(settings_.heading_offset));
315  this->log(LogLevel::DEBUG , "Ant pitch offset: " + std::to_string(settings_.pitch_offset));
316 
317  // ins_initial_heading param
318  param("ins_initial_heading", settings_.ins_initial_heading, std::string("auto"));
319 
320  // ins_std_dev_mask
321  param("ins_std_dev_mask/att_std_dev", settings_.att_std_dev, 5.0f);
322  param("ins_std_dev_mask/pos_std_dev", settings_.pos_std_dev, 10.0f);
323 
324  // INS solution reference point
325  param("ins_use_poi", settings_.ins_use_poi, false);
326 
328  {
329  this->log(LogLevel::ERROR , "If tf shall be published, ins_use_poi has to be set to true! It is set automatically to true.");
330  settings_.ins_use_poi = true;
331  }
332 
333  // Correction service parameters
334  param("ntrip_settings/mode", settings_.ntrip_mode, std::string("off"));
335  param("ntrip_settings/caster", settings_.caster, std::string());
336  getUint32Param("ntrip_settings/caster_port", settings_.caster_port, static_cast<uint32_t>(0));
337  param("ntrip_settings/username", settings_.ntrip_username, std::string());
338  param("ntrip_settings/password", settings_.ntrip_password, std::string());
339  if (settings_.ntrip_password.empty())
340  {
341  uint32_t pwd_tmp;
342  getUint32Param("ntrip_settings/password", pwd_tmp, static_cast<uint32_t>(0));
343  settings_.ntrip_password = std::to_string(pwd_tmp);
344  }
345  param("ntrip_settings/mountpoint", settings_.mountpoint, std::string());
346  param("ntrip_settings/ntrip_version", settings_.ntrip_version, std::string("v2"));
347  param("ntrip_settings/send_gga", settings_.send_gga, std::string("auto"));
348  param("ntrip_settings/rx_has_internet", settings_.rx_has_internet, false);
349  param("ntrip_settings/rtcm_version", settings_.rtcm_version, std::string("RTCMv3"));
350  getUint32Param("ntrip_settings/rx_input_corrections_tcp", settings_.rx_input_corrections_tcp,
351  static_cast<uint32_t>(28785));
352  param("ntrip_settings/rx_input_corrections_serial",
353  settings_.rx_input_corrections_serial, std::string("USB2"));
354 
356  {
358  {
359  this->log(LogLevel::WARN ,"AttEuler needs multi-antenna receiver. Multi-antenna setting automatically activated. Deactivate publishing of AttEuler if multi-antenna operation is not available.");
360  settings_.multi_antenna = true;
361  }
362  }
363 
364  // To be implemented: RTCM, raw data settings, PPP, SBAS ...
365  this->log(LogLevel::DEBUG ,"Finished getROSParams() method");
366  return true;
367 }
368 
369 void rosaic_node::ROSaicNode::getTransform(const std::string& targetFrame, const std::string& sourceFrame, TransformStampedMsg& T_s_t)
370 {
371  bool found = false;
372  while (!found)
373  {
374  try
375  {
376  // try to get tf from source frame to target frame
377  T_s_t = tfBuffer_.lookupTransform(targetFrame, sourceFrame, ros::Time(0), ros::Duration(2.0));
378  found = true;
379  }
380  catch (const tf2::TransformException& ex)
381  {
382  this->log(LogLevel::WARN, "Waiting for transform from " + sourceFrame + " to " + targetFrame + ": " + ex.what() + ".");
383  found = false;
384  }
385  }
386 }
387 
388 void rosaic_node::ROSaicNode::getRPY(const QuaternionMsg& qm, double& roll, double& pitch, double& yaw)
389 {
390  Eigen::Quaterniond q(qm.w, qm.x, qm.y, qm.z);
391  Eigen::Quaterniond::RotationMatrixType C = q.matrix();
392 
393  roll = std::atan2(C(2, 1), C(2, 2));
394  pitch = std::asin(-C(2, 0));
395  yaw = std::atan2(C(1, 0), C(0, 0));
396 }
double theta_z
IMU orientation z-angle.
Definition: rx_message.hpp:184
uint32_t polling_period_rest
Polling period for all other SBF blocks and NMEA messages.
Definition: rx_message.hpp:160
std::string vehicle_frame_id
The frame ID of the vehicle frame.
Definition: rx_message.hpp:318
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
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
geometry_msgs::TransformStamped TransformStampedMsg
Definition: typedefs.hpp:86
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
std::string rtcm_version
RTCM version for NTRIP service (if Rx does not have internet)
Definition: rx_message.hpp:234
void defineMessages()
Defines which Rx messages to read and which ROS messages to publish.
std::string ant_serial_nr
Serial number of your particular Main antenna.
Definition: rx_message.hpp:174
std::string rx_input_corrections_serial
Definition: rx_message.hpp:240
void initializeIO()
Initializes the I/O handling.
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
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
void log(LogLevel logLevel, const std::string &s)
Log function to provide abstraction of ROS loggers.
Definition: typedefs.hpp:208
double wrapAngle180to180(double angle)
Wraps an angle between -180 and 180 degrees.
bool getUint32Param(const std::string &name, uint32_t &val, uint32_t defaultVal)
Gets an integer or unsigned integer value from the parameter server.
Definition: typedefs.hpp:177
void getTransform(const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t)
Gets transforms from tf2.
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
double ant_lever_x
INS antenna lever arm x-offset.
Definition: rx_message.hpp:186
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
bool param(const std::string &name, T &val, const T &defaultVal)
Gets parameter of type T from the parameter server.
Definition: typedefs.hpp:198
std::string aux1_frame_id
The frame ID of the aux1 antenna.
Definition: rx_message.hpp:316
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
bool getROSParams()
Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file...
Definition: rosaic_node.cpp:79
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
bool publish_measepoch
Whether or not to publish the MeasEpoch message.
Definition: rx_message.hpp:252
Settings settings_
Settings.
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
io_comm_rx::Comm_IO IO_
Handles communication with the Rx.
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
bool publish_localization
Whether or not to publish the LocalizationMsg message.
Definition: rx_message.hpp:298
geometry_msgs::Quaternion QuaternionMsg
Definition: typedefs.hpp:84
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
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
bool publish_pvtgeodetic
Whether or not to publish the PVTGeodeticMsg message.
Definition: rx_message.hpp:257
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
void configureRx()
Configures Rx: Which SBF/NMEA messages it should output and later correction settings.
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
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
float att_std_dev
Attitude deviation mask.
Definition: rx_message.hpp:214
void getRPY(const QuaternionMsg &qm, double &roll, double &pitch, double &yaw)
Gets Euler angles from quaternion message.
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
double vsm_z
INS velocity sensor lever arm z-offset.
Definition: rx_message.hpp:202
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::string datum
Datum to be used.
Definition: rx_message.hpp:156
double theta_y
IMU orientation y-angle.
Definition: rx_message.hpp:182
std::unique_ptr< tf2_ros::TransformListener > tfListener_
bool publish_gpgsv
Whether or not to publish the GSV message.
Definition: rx_message.hpp:250
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
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
tf2_ros::Buffer tfBuffer_
tf2 buffer and listener
std::string ins_initial_heading
For heading computation when unit is powered-cycled.
Definition: rx_message.hpp:212
#define ROSCONSOLE_DEFAULT_NAME
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
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
float delta_u
Marker-to-ARP offset in the upward direction.
Definition: rx_message.hpp:166
The heart of the ROSaic driver: The ROS node that represents it.
double ant_lever_z
INS antenna lever arm z-offset.
Definition: rx_message.hpp:190
std::string ant_type
Definition: rx_message.hpp:169


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