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>
34 
42 {
43  param("activate_debug_log", settings_.activate_debug_log, false);
45  {
48  ros::console::levels::Debug)) // debug is lowest level, shows
49  // everything
51  }
52 
53  this->log(log_level::DEBUG, "Called ROSaicNode() constructor..");
54 
56 
57  // Parameters must be set before initializing IO
58  if (!getROSParams())
59  return;
60 
61  // Initializes Connection
62  IO_.connect();
63 
64  this->log(log_level::DEBUG, "Leaving ROSaicNode() constructor..");
65 }
66 
68 {
69  param("use_gnss_time", settings_.use_gnss_time, true);
70  param("latency_compensation", settings_.latency_compensation, false);
71  param("frame_id", settings_.frame_id, static_cast<std::string>("gnss"));
72  param("imu_frame_id", settings_.imu_frame_id, static_cast<std::string>("imu"));
73  param("poi_frame_id", settings_.poi_frame_id,
74  static_cast<std::string>("base_link"));
75  param("vsm_frame_id", settings_.vsm_frame_id, static_cast<std::string>("vsm"));
76  param("aux1_frame_id", settings_.aux1_frame_id,
77  static_cast<std::string>("aux1"));
78  param("vehicle_frame_id", settings_.vehicle_frame_id, settings_.poi_frame_id);
79  param("local_frame_id", settings_.local_frame_id,
80  static_cast<std::string>("odom"));
81  param("insert_local_frame", settings_.insert_local_frame, false);
82  param("lock_utm_zone", settings_.lock_utm_zone, true);
83  param("leap_seconds", settings_.leap_seconds, -128);
84 
85  param("configure_rx", settings_.configure_rx, true);
86 
87  // Communication parameters
88  param("device", settings_.device, static_cast<std::string>("/dev/ttyACM0"));
89  getUint32Param("serial/baudrate", settings_.baudrate,
90  static_cast<uint32_t>(921600));
91  param("serial/hw_flow_control", settings_.hw_flow_control,
92  static_cast<std::string>("off"));
93  getUint32Param("stream_device/tcp/port", settings_.tcp_port,
94  static_cast<uint32_t>(0));
95  param("stream_device/tcp/ip_server", settings_.tcp_ip_server,
96  static_cast<std::string>(""));
97  getUint32Param("stream_device/udp/port", settings_.udp_port,
98  static_cast<uint32_t>(0));
99  param("stream_device/udp/unicast_ip", settings_.udp_unicast_ip,
100  static_cast<std::string>(""));
101  param("stream_device/udp/ip_server", settings_.udp_ip_server,
102  static_cast<std::string>(""));
103  param("login/user", settings_.login_user, static_cast<std::string>(""));
104  param("login/password", settings_.login_password, static_cast<std::string>(""));
105  settings_.reconnect_delay_s = 2.0f; // Removed from ROS parameter list.
106  param("receiver_type", settings_.septentrio_receiver_type,
107  static_cast<std::string>("gnss"));
108  if (!((settings_.septentrio_receiver_type == "gnss") ||
109  (settings_.septentrio_receiver_type == "ins")))
110  {
111  this->log(log_level::FATAL, "Unkown septentrio_receiver_type " +
112  settings_.septentrio_receiver_type +
113  " use either gnss or ins.");
114  return false;
115  }
116 
117  if (settings_.configure_rx && !settings_.tcp_ip_server.empty() &&
118  !settings_.udp_ip_server.empty())
119  {
120  this->log(
122  "Both UDP and TCP have been defined to receive data, only TCP will be used. If UDP is intended, leave tcp/ip_server empty.");
123  }
124 
125  // Polling period parameters
126  getUint32Param("polling_period/pvt", settings_.polling_period_pvt,
127  static_cast<uint32_t>(1000));
128  if (!(validPeriod(settings_.polling_period_pvt,
129  settings_.septentrio_receiver_type == "ins")))
130  {
131  this->log(
133  "Please specify a valid polling period for PVT-related SBF blocks and NMEA messages.");
134  return false;
135  }
136  getUint32Param("polling_period/rest", settings_.polling_period_rest,
137  static_cast<uint32_t>(1000));
138  if (!(validPeriod(settings_.polling_period_rest,
139  settings_.septentrio_receiver_type == "ins")))
140  {
141  this->log(
143  "Please specify a valid polling period for PVT-unrelated SBF blocks and NMEA messages.");
144  return false;
145  }
146 
147  // OSNMA parameters
148  param("osnma/mode", settings_.osnma.mode, std::string("off"));
149  param("osnma/ntp_server", settings_.osnma.ntp_server, std::string(""));
150  param("osnma/keep_open", settings_.osnma.keep_open, true);
151 
152  // multi_antenna param
153  param("multi_antenna", settings_.multi_antenna, false);
154 
155  // Publishing parameters
156  param("publish/gpst", settings_.publish_gpst, false);
157  param("publish/navsatfix", settings_.publish_navsatfix, true);
158  param("publish/gpsfix", settings_.publish_gpsfix, false);
159  param("publish/pose", settings_.publish_pose, false);
160  param("publish/diagnostics", settings_.publish_diagnostics, false);
161  param("publish/aimplusstatus", settings_.publish_aimplusstatus, false);
162  param("publish/galauthstatus", settings_.publish_galauthstatus, false);
163  param("publish/gpgga", settings_.publish_gpgga, false);
164  param("publish/gprmc", settings_.publish_gprmc, false);
165  param("publish/gpgsa", settings_.publish_gpgsa, false);
166  param("publish/gpgsv", settings_.publish_gpgsv, false);
167  param("publish/measepoch", settings_.publish_measepoch, false);
168  param("publish/pvtcartesian", settings_.publish_pvtcartesian, false);
169  param("publish/pvtgeodetic", settings_.publish_pvtgeodetic, false);
170  param("publish/basevectorcart", settings_.publish_basevectorcart, false);
171  param("publish/basevectorgeod", settings_.publish_basevectorgeod, false);
172  param("publish/poscovcartesian", settings_.publish_poscovcartesian, false);
173  param("publish/poscovgeodetic", settings_.publish_poscovgeodetic, false);
174  param("publish/velcovcartesian", settings_.publish_velcovcartesian, false);
175  param("publish/velcovgeodetic", settings_.publish_velcovgeodetic, false);
176  param("publish/atteuler", settings_.publish_atteuler, false);
177  param("publish/attcoveuler", settings_.publish_attcoveuler, false);
178  param("publish/insnavcart", settings_.publish_insnavcart, false);
179  param("publish/insnavgeod", settings_.publish_insnavgeod, false);
180  param("publish/imusetup", settings_.publish_imusetup, false);
181  param("publish/velsensorsetup", settings_.publish_velsensorsetup, false);
182  param("publish/exteventinsnavgeod", settings_.publish_exteventinsnavgeod, false);
183  param("publish/exteventinsnavcart", settings_.publish_exteventinsnavcart, false);
184  param("publish/extsensormeas", settings_.publish_extsensormeas, false);
185  param("publish/imu", settings_.publish_imu, false);
186  param("publish/localization", settings_.publish_localization, false);
187  param("publish/localization_ecef", settings_.publish_localization_ecef, false);
188  param("publish/twist", settings_.publish_twist, false);
189  param("publish/tf", settings_.publish_tf, false);
190  param("publish/tf_ecef", settings_.publish_tf_ecef, false);
191 
192  if (settings_.publish_tf && settings_.publish_tf_ecef)
193  {
194  this->log(
196  "Only one of the tfs may be published at once, just activating tf in ECEF ");
197  settings_.publish_tf = false;
198  }
199 
200  // Datum and marker-to-ARP offset
201  param("datum", settings_.datum, std::string("Default"));
202  // WGS84 is equivalent to Default and kept for backwards compatibility
203  if (settings_.datum == "Default")
204  settings_.datum = "WGS84";
205  param("ant_type", settings_.ant_type, std::string("Unknown"));
206  param("ant_aux1_type", settings_.ant_aux1_type, std::string("Unknown"));
207  param("ant_serial_nr", settings_.ant_serial_nr, std::string());
208  if (settings_.ant_serial_nr.empty())
209  {
210  uint32_t sn_tmp;
211  if (getUint32Param("ant_serial_nr", sn_tmp, static_cast<uint32_t>(0)))
212  settings_.ant_serial_nr = std::to_string(sn_tmp);
213  else
214  settings_.ant_serial_nr = "Unknown";
215  }
216  param("ant_aux1_serial_nr", settings_.ant_aux1_serial_nr, std::string());
217  if (settings_.ant_aux1_serial_nr.empty())
218  {
219  uint32_t sn_tmp;
220  if (getUint32Param("ant_aux1_serial_nr", sn_tmp, static_cast<uint32_t>(0)))
221  settings_.ant_aux1_serial_nr = std::to_string(sn_tmp);
222  else
223  settings_.ant_aux1_serial_nr = "Unknown";
224  }
225  param("poi_to_arp/delta_e", settings_.delta_e, 0.0f);
226  param("poi_to_arp/delta_n", settings_.delta_n, 0.0f);
227  param("poi_to_arp/delta_u", settings_.delta_u, 0.0f);
228 
229  param("use_ros_axis_orientation", settings_.use_ros_axis_orientation, true);
230 
231  // INS Spatial Configuration
232  bool getConfigFromTf;
233  param("get_spatial_config_from_tf", getConfigFromTf, false);
234  if (getConfigFromTf)
235  {
236  if (settings_.septentrio_receiver_type == "ins")
237  {
238  TransformStampedMsg T_imu_vehicle;
239  getTransform(settings_.vehicle_frame_id, settings_.imu_frame_id,
240  T_imu_vehicle);
241  TransformStampedMsg T_poi_imu;
242  getTransform(settings_.imu_frame_id, settings_.poi_frame_id, T_poi_imu);
243  TransformStampedMsg T_vsm_imu;
244  getTransform(settings_.imu_frame_id, settings_.vsm_frame_id, T_vsm_imu);
245  TransformStampedMsg T_ant_imu;
246  getTransform(settings_.imu_frame_id, settings_.frame_id, T_ant_imu);
247 
248  // IMU orientation parameter
249  double roll, pitch, yaw;
250  getRPY(T_imu_vehicle.transform.rotation, roll, pitch, yaw);
251  settings_.theta_x = parsing_utilities::rad2deg(roll);
252  settings_.theta_y = parsing_utilities::rad2deg(pitch);
253  settings_.theta_z = parsing_utilities::rad2deg(yaw);
254  // INS antenna lever arm offset parameter
255  settings_.ant_lever_x = T_ant_imu.transform.translation.x;
256  settings_.ant_lever_y = T_ant_imu.transform.translation.y;
257  settings_.ant_lever_z = T_ant_imu.transform.translation.z;
258  // INS POI ofset paramter
259  settings_.poi_x = T_poi_imu.transform.translation.x;
260  settings_.poi_y = T_poi_imu.transform.translation.y;
261  settings_.poi_z = T_poi_imu.transform.translation.z;
262  // INS velocity sensor lever arm offset parameter
263  settings_.vsm_x = T_vsm_imu.transform.translation.x;
264  settings_.vsm_y = T_vsm_imu.transform.translation.y;
265  settings_.vsm_z = T_vsm_imu.transform.translation.z;
266 
267  if (settings_.multi_antenna)
268  {
269  TransformStampedMsg T_aux1_imu;
270  getTransform(settings_.imu_frame_id, settings_.aux1_frame_id,
271  T_aux1_imu);
272  // Antenna Attitude Determination parameter
273  double dy = T_aux1_imu.transform.translation.y -
274  T_ant_imu.transform.translation.y;
275  double dx = T_aux1_imu.transform.translation.x -
276  T_ant_imu.transform.translation.x;
277  settings_.heading_offset =
278  parsing_utilities::rad2deg(std::atan2(dy, dx));
279  double dz = T_aux1_imu.transform.translation.z -
280  T_ant_imu.transform.translation.z;
281  double dr = std::sqrt(parsing_utilities::square(dx) +
283  settings_.pitch_offset =
284  parsing_utilities::rad2deg(std::atan2(-dz, dr));
285  }
286  }
287  if ((settings_.septentrio_receiver_type == "gnss") &&
288  settings_.multi_antenna)
289  {
290  TransformStampedMsg T_ant_vehicle;
291  getTransform(settings_.vehicle_frame_id, settings_.frame_id,
292  T_ant_vehicle);
293  TransformStampedMsg T_aux1_vehicle;
294  getTransform(settings_.vehicle_frame_id, settings_.aux1_frame_id,
295  T_aux1_vehicle);
296 
297  // Antenna Attitude Determination parameter
298  double dy = T_aux1_vehicle.transform.translation.y -
299  T_ant_vehicle.transform.translation.y;
300  double dx = T_aux1_vehicle.transform.translation.x -
301  T_ant_vehicle.transform.translation.x;
302  settings_.heading_offset =
303  parsing_utilities::rad2deg(std::atan2(dy, dx));
304  double dz = T_aux1_vehicle.transform.translation.z -
305  T_ant_vehicle.transform.translation.z;
306  double dr = std::sqrt(parsing_utilities::square(dx) +
308  settings_.pitch_offset = parsing_utilities::rad2deg(std::atan2(-dz, dr));
309  }
310  } else
311  {
312  // IMU orientation parameter
313  param("ins_spatial_config/imu_orientation/theta_x", settings_.theta_x, 0.0);
314  param("ins_spatial_config/imu_orientation/theta_y", settings_.theta_y, 0.0);
315  param("ins_spatial_config/imu_orientation/theta_z", settings_.theta_z, 0.0);
316  // INS antenna lever arm offset parameter
317  param("ins_spatial_config/ant_lever_arm/x", settings_.ant_lever_x, 0.0);
318  param("ins_spatial_config/ant_lever_arm/y", settings_.ant_lever_y, 0.0);
319  param("ins_spatial_config/ant_lever_arm/z", settings_.ant_lever_z, 0.0);
320  // INS POI ofset paramter
321  param("ins_spatial_config/poi_lever_arm/delta_x", settings_.poi_x, 0.0);
322  param("ins_spatial_config/poi_lever_arm/delta_y", settings_.poi_y, 0.0);
323  param("ins_spatial_config/poi_lever_arm/delta_z", settings_.poi_z, 0.0);
324  // INS velocity sensor lever arm offset parameter
325  param("ins_spatial_config/vsm_lever_arm/vsm_x", settings_.vsm_x, 0.0);
326  param("ins_spatial_config/vsm_lever_arm/vsm_y", settings_.vsm_y, 0.0);
327  param("ins_spatial_config/vsm_lever_arm/vsm_z", settings_.vsm_z, 0.0);
328  // Antenna Attitude Determination parameter
329  param("att_offset/heading", settings_.heading_offset, 0.0);
330  param("att_offset/pitch", settings_.pitch_offset, 0.0);
331  }
332 
333  if (settings_.use_ros_axis_orientation)
334  {
335  settings_.theta_x =
336  parsing_utilities::wrapAngle180to180(settings_.theta_x + 180.0);
337  settings_.theta_y *= -1.0;
338  settings_.theta_z *= -1.0;
339  settings_.ant_lever_y *= -1.0;
340  settings_.ant_lever_z *= -1.0;
341  settings_.poi_y *= -1.0;
342  settings_.poi_z *= -1.0;
343  settings_.vsm_y *= -1.0;
344  settings_.vsm_z *= -1.0;
345  settings_.heading_offset *= -1.0;
346  settings_.pitch_offset *= -1.0;
347  }
348 
349  if (std::abs(settings_.heading_offset) > std::numeric_limits<double>::epsilon())
350  {
351  if (settings_.publish_atteuler)
352  {
353  this->log(
355  "Pitch angle output by topic /atteuler is a tilt angle rotated by " +
356  std::to_string(settings_.heading_offset) + ".");
357  }
358  if (settings_.publish_pose && (settings_.septentrio_receiver_type == "gnss"))
359  {
360  this->log(
362  "Pitch angle output by topic /pose is a tilt angle rotated by " +
363  std::to_string(settings_.heading_offset) + ".");
364  }
365  }
366 
367  this->log(log_level::DEBUG,
368  "IMU roll offset: " + std::to_string(settings_.theta_x));
369  this->log(log_level::DEBUG,
370  "IMU pitch offset: " + std::to_string(settings_.theta_y));
371  this->log(log_level::DEBUG,
372  "IMU yaw offset: " + std::to_string(settings_.theta_z));
373  this->log(log_level::DEBUG,
374  "Ant heading offset: " + std::to_string(settings_.heading_offset));
375  this->log(log_level::DEBUG,
376  "Ant pitch offset: " + std::to_string(settings_.pitch_offset));
377 
378  // ins_initial_heading param
379  param("ins_initial_heading", settings_.ins_initial_heading, std::string("auto"));
380 
381  // ins_std_dev_mask
382  param("ins_std_dev_mask/att_std_dev", settings_.att_std_dev, 5.0f);
383  param("ins_std_dev_mask/pos_std_dev", settings_.pos_std_dev, 10.0f);
384 
385  // INS solution reference point
386  param("ins_use_poi", settings_.ins_use_poi, false);
387 
388  if (settings_.publish_tf && !settings_.ins_use_poi)
389  {
390  this->log(
392  "If tf shall be published, ins_use_poi has to be set to true! It is set automatically to true.");
393  settings_.ins_use_poi = true;
394  }
395 
396  // RTK correction parameters
397  // NTRIP
398  for (uint8_t i = 1; i < 4; ++i)
399  {
400  RtkNtrip ntripSettings;
401  std::string ntrip = "ntrip_" + std::to_string(i);
402 
403  param("rtk_settings/" + ntrip + "/id", ntripSettings.id, std::string());
404  if (ntripSettings.id.empty())
405  continue;
406 
407  param("rtk_settings/" + ntrip + "/caster", ntripSettings.caster,
408  std::string());
409  getUint32Param("rtk_settings/" + ntrip + "/caster_port",
410  ntripSettings.caster_port, static_cast<uint32_t>(0));
411  param("rtk_settings/" + ntrip + "/username", ntripSettings.username,
412  std::string());
413  if (!param("rtk_settings/" + ntrip + "/password", ntripSettings.password,
414  std::string()))
415  {
416  uint32_t pwd_tmp;
417  getUint32Param("rtk_settings/" + ntrip + "/password", pwd_tmp,
418  static_cast<uint32_t>(0));
419  ntripSettings.password = std::to_string(pwd_tmp);
420  }
421  param("rtk_settings/" + ntrip + "/mountpoint", ntripSettings.mountpoint,
422  std::string());
423  param("rtk_settings/" + ntrip + "/version", ntripSettings.version,
424  std::string("v2"));
425  param("rtk_settings/" + ntrip + "/tls", ntripSettings.tls, false);
426  if (ntripSettings.tls)
427  param("rtk_settings/" + ntrip + "/fingerprint",
428  ntripSettings.fingerprint, std::string(""));
429  param("rtk_settings/" + ntrip + "/rtk_standard", ntripSettings.rtk_standard,
430  std::string("auto"));
431  param("rtk_settings/" + ntrip + "/send_gga", ntripSettings.send_gga,
432  std::string("auto"));
433  if (ntripSettings.send_gga.empty())
434  ntripSettings.send_gga = "off";
435  param("rtk_settings/" + ntrip + "/keep_open", ntripSettings.keep_open, true);
436 
437  settings_.rtk.ntrip.push_back(ntripSettings);
438  }
439  // IP server
440  for (uint8_t i = 1; i < 6; ++i)
441  {
442  RtkIpServer ipSettings;
443  std::string ips = "ip_server_" + std::to_string(i);
444 
445  param("rtk_settings/" + ips + "/id", ipSettings.id, std::string(""));
446  if (ipSettings.id.empty())
447  continue;
448 
449  getUint32Param("rtk_settings/" + ips + "/port", ipSettings.port,
450  static_cast<uint32_t>(0));
451  param("rtk_settings/" + ips + "/rtk_standard", ipSettings.rtk_standard,
452  std::string("auto"));
453  param("rtk_settings/" + ips + "/send_gga", ipSettings.send_gga,
454  std::string("auto"));
455  if (ipSettings.send_gga.empty())
456  ipSettings.send_gga = "off";
457  param("rtk_settings/" + ips + "/keep_open", ipSettings.keep_open, true);
458 
459  settings_.rtk.ip_server.push_back(ipSettings);
460  }
461  // Serial
462  for (uint8_t i = 1; i < 6; ++i)
463  {
464  RtkSerial serialSettings;
465  std::string serial = "serial_" + std::to_string(i);
466 
467  param("rtk_settings/" + serial + "/port", serialSettings.port,
468  std::string());
469  if (serialSettings.port.empty())
470  continue;
471 
472  getUint32Param("rtk_settings/" + serial + "/baud_rate",
473  serialSettings.baud_rate, static_cast<uint32_t>(115200));
474  param("rtk_settings/" + serial + "/rtk_standard",
475  serialSettings.rtk_standard, std::string("auto"));
476  param("rtk_settings/" + serial + "/send_gga", serialSettings.send_gga,
477  std::string("auto"));
478  if (serialSettings.send_gga.empty())
479  serialSettings.send_gga = "off";
480  param("rtk_settings/" + serial + "/keep_open", serialSettings.keep_open,
481  true);
482 
483  settings_.rtk.serial.push_back(serialSettings);
484  }
485 
486  {
487  // deprecation warnings
488  std::string tempString;
489  int32_t tempInt;
490  bool tempBool;
491  param("ntrip_settings/mode", tempString, std::string(""));
492  if (tempString != "")
493  this->log(
495  "Deprecation warning: parameter ntrip_settings/mode has been removed, see README under section rtk_settings.");
496  param("ntrip_settings/caster", tempString, std::string(""));
497  if (tempString != "")
498  this->log(
500  "Deprecation warning: parameter ntrip_settings/caster has been removed, see README under section rtk_settings.");
501  param("ntrip_settings/rx_has_internet", tempBool, false);
502  if (tempBool)
503  this->log(
505  "Deprecation warning: parameter ntrip_settings/rx_has_internet has been removed, see README under section rtk_settings.");
506  param("ntrip_settings/rx_input_corrections_tcp", tempInt, 0);
507  if (tempInt != 0)
508  this->log(
510  "Deprecation warning: parameter ntrip_settings/rx_input_corrections_tcp has been removed, see README under section rtk_settings.");
511  param("ntrip_settings/rx_input_corrections_serial", tempString,
512  std::string(""));
513  if (tempString != "")
514  this->log(
516  "Deprecation warning: parameter ntrip_settings/rx_input_corrections_serial has been removed, see README under section rtk_settings.");
517  }
518 
519  if (settings_.publish_atteuler)
520  {
521  if (!settings_.multi_antenna)
522  {
523  this->log(
525  "AttEuler needs multi-antenna receiver. Multi-antenna setting automatically activated. Deactivate publishing of AttEuler if multi-antenna operation is not available.");
526  settings_.multi_antenna = true;
527  }
528  }
529 
530  // VSM - velocity sensor measurements for INS
531  if (settings_.septentrio_receiver_type == "ins")
532  {
533  param("ins_vsm/ros/source", settings_.ins_vsm_ros_source, std::string(""));
534 
535  bool ins_use_vsm = false;
536  ins_use_vsm = ((settings_.ins_vsm_ros_source == "odometry") ||
537  (settings_.ins_vsm_ros_source == "twist"));
538  if (!settings_.ins_vsm_ros_source.empty() && !ins_use_vsm)
539  this->log(log_level::ERROR, "unknown ins_vsm/ros/source " +
540  settings_.ins_vsm_ros_source +
541  " -> VSM input will not be used!");
542  param("ins_vsm/ip_server/id", settings_.ins_vsm_ip_server_id,
543  std::string(""));
544  if (!settings_.ins_vsm_ip_server_id.empty())
545  {
546  getUint32Param("ins_vsm/ip_server/port",
547  settings_.ins_vsm_ip_server_port,
548  static_cast<uint32_t>(0));
549  param("ins_vsm/ip_server/keep_open",
550  settings_.ins_vsm_ip_server_keep_open, true);
551  this->log(
553  "external velocity sensor measurements via ip_server are used.");
554  }
555 
556  param("ins_vsm/serial/port", settings_.ins_vsm_serial_port, std::string(""));
557  if (!settings_.ins_vsm_serial_port.empty())
558  {
559  getUint32Param("ins_vsm/serial/baud_rate",
560  settings_.ins_vsm_serial_baud_rate,
561  static_cast<uint32_t>(115200));
562  param("ins_vsm/serial/keep_open", settings_.ins_vsm_serial_keep_open,
563  true);
564  this->log(log_level::INFO,
565  "external velocity sensor measurements via serial are used.");
566  }
567 
568  param("ins_vsm/ros/config", settings_.ins_vsm_ros_config,
569  std::vector<bool>());
570  if (ins_use_vsm && (settings_.ins_vsm_ros_config.size() == 3))
571  {
572  if (std::all_of(settings_.ins_vsm_ros_config.begin(),
573  settings_.ins_vsm_ros_config.end(),
574  [](bool v) { return !v; }))
575  {
576  ins_use_vsm = false;
577  this->log(
579  "all elements of ins_vsm/ros/config have been set to false -> VSM input will not be used!");
580  } else
581  {
582  param("ins_vsm/ros/variances_by_parameter",
583  settings_.ins_vsm_ros_variances_by_parameter, false);
584  if (settings_.ins_vsm_ros_variances_by_parameter)
585  {
586  param("ins_vsm/ros/variances", settings_.ins_vsm_ros_variances,
587  std::vector<double>());
588  if (settings_.ins_vsm_ros_variances.size() != 3)
589  {
590  this->log(
592  "ins_vsm/ros/variances has to be of size 3 for var_x, var_y, and var_z -> VSM input will not be used!");
593  ins_use_vsm = false;
594  settings_.ins_vsm_ros_source = "";
595  } else
596  {
597  for (size_t i = 0; i < settings_.ins_vsm_ros_config.size();
598  ++i)
599  {
600  if (settings_.ins_vsm_ros_config[i] &&
601  (settings_.ins_vsm_ros_variances[i] <= 0.0))
602  {
603  this->log(
605  "ins_vsm/ros/config of element " +
606  std::to_string(i) +
607  " has been set to be used but its variance is not > 0.0 -> its VSM input will not be used!");
608  settings_.ins_vsm_ros_config[i] = false;
609  }
610  }
611  }
612  if (std::all_of(settings_.ins_vsm_ros_config.begin(),
613  settings_.ins_vsm_ros_config.end(),
614  [](bool v) { return !v; }))
615  {
616  ins_use_vsm = false;
617  settings_.ins_vsm_ros_source = "";
618  this->log(
620  "all elements of ins_vsm/ros/config have been set to false due to invalid covariances -> VSM input will not be used!");
621  }
622  }
623  }
624  } else if (ins_use_vsm)
625  {
626  settings_.ins_vsm_ros_source = "";
627  this->log(
629  "ins_vsm/ros/config has to be of size 3 to signal wether to use v_x, v_y, and v_z -> VSM input will not be used!");
630  }
631  if (ins_use_vsm)
632  {
633  this->log(log_level::INFO, "ins_vsm/ros/source " +
634  settings_.ins_vsm_ros_source +
635  " will be used.");
636  registerSubscriber();
637  }
638 
639  if (!settings_.tcp_ip_server.empty())
640  {
641  if (settings_.tcp_ip_server == settings_.udp_ip_server)
642  this->log(
644  "tcp/ip_server and udp/ip_server cannot use the same IP server");
645  if (settings_.tcp_ip_server == settings_.ins_vsm_ip_server_id)
646  this->log(
648  "tcp/ip_server and ins_vsm/ip_server/id cannot use the same IP server");
649  for (size_t i = 0; i < settings_.rtk.ip_server.size(); ++i)
650  {
651  if (settings_.tcp_ip_server == settings_.rtk.ip_server[i].id)
652  this->log(log_level::ERROR,
653  "tcp/ip_server and rtk_settings/ip_server_" +
654  std::to_string(i + 1) +
655  "/id cannot use the same IP server");
656  }
657  }
658  if (!settings_.udp_ip_server.empty())
659  {
660  if (settings_.udp_ip_server == settings_.ins_vsm_ip_server_id)
661  this->log(
663  "udp/ip_server and ins_vsm/ip_server/id cannot use the same IP server");
664  for (size_t i = 0; i < settings_.rtk.ip_server.size(); ++i)
665  {
666  if (settings_.udp_ip_server == settings_.rtk.ip_server[i].id)
667  this->log(log_level::ERROR,
668  "udp/ip_server and rtk_settings/ip_server_" +
669  std::to_string(i + 1) +
670  "/id cannot use the same IP server");
671  }
672  }
673  if (!settings_.ins_vsm_ip_server_id.empty())
674  {
675  for (size_t i = 0; i < settings_.rtk.ip_server.size(); ++i)
676  {
677  if (settings_.ins_vsm_ip_server_id == settings_.rtk.ip_server[i].id)
678  this->log(log_level::ERROR,
679  "ins_vsm/ip_server/id and rtk_settings/ip_server_" +
680  std::to_string(i + 1) +
681  "/id cannot use the same IP server");
682  }
683  }
684  if (settings_.rtk.ip_server.size() == 2)
685  {
686  if (!settings_.rtk.ip_server[0].id.empty() &&
687  (settings_.rtk.ip_server[0].id == settings_.rtk.ip_server[1].id))
688  this->log(
690  "rtk_settings/ip_server_1/id and rtk_settings/ip_server_2/id cannot use the same IP server");
691  }
692  }
693 
694  boost::smatch match;
695  if (boost::regex_match(settings_.device, match,
696  boost::regex("(tcp)://(.+):(\\d+)")))
697  {
698  settings_.device_tcp_ip = match[2];
699  settings_.device_tcp_port = match[3];
700  settings_.device_type = device_type::TCP;
701  } else if (boost::regex_match(settings_.device, match,
702  boost::regex("(file_name):(/|(?:/[\\w-]+)+.sbf)")))
703  {
704  settings_.read_from_sbf_log = true;
705  settings_.use_gnss_time = true;
706  settings_.device = match[2];
707  settings_.device_type = device_type::SBF_FILE;
708  } else if (boost::regex_match(
709  settings_.device, match,
710  boost::regex("(file_name):(/|(?:/[\\w-]+)+.pcap)")))
711  {
712  settings_.read_from_pcap = true;
713  settings_.use_gnss_time = true;
714  settings_.device = match[2];
715  settings_.device_type = device_type::PCAP_FILE;
716  } else if (boost::regex_match(settings_.device, match,
717  boost::regex("(serial):(.+)")))
718  {
719  std::string proto(match[2]);
720  settings_.device_type = device_type::SERIAL;
721  settings_.device = proto;
722  } else
723  {
724  if (settings_.udp_ip_server.empty() || settings_.configure_rx ||
725  (settings_.ins_vsm_ros_source == "odometry") ||
726  (settings_.ins_vsm_ros_source == "twist"))
727  {
728  std::stringstream ss;
729  ss << "Device is unsupported. Perhaps you meant 'tcp://host:port' or 'file_name:xxx.sbf' or 'serial:/path/to/device'?";
730  this->log(log_level::ERROR, ss.str());
731  return false;
732  }
733  }
734 
735  // To be implemented: RTCM, raw data settings, PPP, SBAS ...
736  this->log(log_level::DEBUG, "Finished getROSParams() method");
737  return true;
738 }
739 
740 [[nodiscard]] bool rosaic_node::ROSaicNode::validPeriod(uint32_t period,
741  bool isIns) const
742 {
743  return ((period == 0) || ((period == 5 && isIns)) || (period == 10) ||
744  (period == 20) || (period == 40) || (period == 50) || (period == 100) ||
745  (period == 200) || (period == 500) || (period == 1000) ||
746  (period == 2000) || (period == 5000) || (period == 10000) ||
747  (period == 15000) || (period == 30000) || (period == 60000) ||
748  (period == 120000) || (period == 300000) || (period == 600000) ||
749  (period == 900000) || (period == 1800000) || (period == 3600000));
750 }
751 
752 void rosaic_node::ROSaicNode::getTransform(const std::string& targetFrame,
753  const std::string& sourceFrame,
754  TransformStampedMsg& T_s_t) const
755 {
756  bool found = false;
757  while (!found)
758  {
759  try
760  {
761  // try to get tf from source frame to target frame
762  T_s_t = tfBuffer_.lookupTransform(targetFrame, sourceFrame, ros::Time(0),
763  ros::Duration(2.0));
764  found = true;
765  } catch (const tf2::TransformException& ex)
766  {
767  this->log(log_level::WARN, "Waiting for transform from " + sourceFrame +
768  " to " + targetFrame + ": " + ex.what() +
769  ".");
770  found = false;
771  }
772  }
773 }
774 
775 void rosaic_node::ROSaicNode::getRPY(const QuaternionMsg& qm, double& roll,
776  double& pitch, double& yaw) const
777 {
778  Eigen::Quaterniond q(qm.w, qm.x, qm.y, qm.z);
779  Eigen::Quaterniond::RotationMatrixType C = q.matrix();
780 
781  roll = std::atan2(C(2, 1), C(2, 2));
782  pitch = std::asin(-C(2, 0));
783  yaw = std::atan2(C(1, 0), C(0, 0));
784 }
785 
786 void rosaic_node::ROSaicNode::sendVelocity(const std::string& velNmea)
787 {
788  IO_.sendVelocity(velNmea);
789 }
log_level::DEBUG
@ DEBUG
Definition: typedefs.hpp:172
device_type::TCP
@ TCP
Definition: settings.hpp:115
RtkNtrip::id
std::string id
Id of the NTRIP port.
Definition: settings.hpp:50
rosaic_node::ROSaicNode::IO_
io::CommunicationCore IO_
Handles communication with the Rx.
Definition: rosaic_node.hpp:130
ROSaicNodeBase::log
void log(log_level::LogLevel logLevel, const std::string &s) const
Log function to provide abstraction of ROS loggers.
Definition: typedefs.hpp:257
rosaic_node::ROSaicNode::getTransform
void getTransform(const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t) const
Gets transforms from tf2.
Definition: rosaic_node.cpp:752
RtkIpServer::keep_open
bool keep_open
Wether RTK connections shall be kept open on shutdown.
Definition: settings.hpp:87
parsing_utilities::rad2deg
T rad2deg(T rad)
Definition: parsing_utilities.hpp:88
RtkSerial::baud_rate
uint32_t baud_rate
Baud rate of the serial port on which Rx receives the corrections.
Definition: settings.hpp:96
parsing_utilities::wrapAngle180to180
double wrapAngle180to180(double angle)
Wraps an angle between -180 and 180 degrees.
Definition: parsing_utilities.cpp:51
rosaic_node::ROSaicNode::validPeriod
bool validPeriod(uint32_t period, bool isIns) const
Checks if the period has a valid value.
Definition: rosaic_node.cpp:740
RtkNtrip::tls
bool tls
Wether to use TLS.
Definition: settings.hpp:64
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
RtkSerial::port
std::string port
Definition: settings.hpp:94
Settings::activate_debug_log
bool activate_debug_log
Set logger level to DEBUG.
Definition: settings.hpp:126
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
log_level::INFO
@ INFO
Definition: typedefs.hpp:173
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
tf2_ros::TransformListener
RtkNtrip::fingerprint
std::string fingerprint
Self-signed certificate fingerprint.
Definition: settings.hpp:66
RtkNtrip::caster
std::string caster
Hostname or IP address of the NTRIP caster to connect to.
Definition: settings.hpp:52
ros::console::levels::Debug
Debug
rosaic_node::ROSaicNode::tfListener_
std::unique_ptr< tf2_ros::TransformListener > tfListener_
Definition: rosaic_node.hpp:133
rosaic_node.hpp
The heart of the ROSaic driver: The ROS node that represents it.
rosaic_node::ROSaicNode::sendVelocity
void sendVelocity(const std::string &velNmea)
Send velocity to communication layer (virtual)
Definition: rosaic_node.cpp:786
RtkNtrip
Definition: settings.hpp:47
device_type::SBF_FILE
@ SBF_FILE
Definition: settings.hpp:117
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
rosaic_node::ROSaicNode::getROSParams
bool getROSParams()
Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file.
Definition: rosaic_node.cpp:67
RtkNtrip::version
std::string version
NTRIP version for NTRIP service.
Definition: settings.hpp:62
parsing_utilities::square
T square(T val)
Definition: parsing_utilities.hpp:60
TransformStampedMsg
geometry_msgs::TransformStamped TransformStampedMsg
Definition: typedefs.hpp:102
log_level::ERROR
@ ERROR
Definition: typedefs.hpp:175
device_type::SERIAL
@ SERIAL
Definition: settings.hpp:116
RtkNtrip::rtk_standard
std::string rtk_standard
RTCM version for correction data.
Definition: settings.hpp:68
RtkIpServer::port
uint32_t port
Definition: settings.hpp:81
ROSaicNodeBase::settings_
Settings settings_
Settings.
Definition: typedefs.hpp:545
RtkNtrip::username
std::string username
Username for NTRIP service.
Definition: settings.hpp:56
rosaic_node::ROSaicNode::getRPY
void getRPY(const QuaternionMsg &qm, double &roll, double &pitch, double &yaw) const
Gets Euler angles from quaternion message.
Definition: rosaic_node.cpp:775
RtkSerial::rtk_standard
std::string rtk_standard
RTCM version for correction data.
Definition: settings.hpp:98
rosaic_node::ROSaicNode::ROSaicNode
ROSaicNode()
Definition: rosaic_node.cpp:41
device_type::PCAP_FILE
@ PCAP_FILE
Definition: settings.hpp:118
RtkIpServer::rtk_standard
std::string rtk_standard
RTCM version for correction data.
Definition: settings.hpp:83
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
ros::Time
ROSaicNodeBase::param
bool param(const std::string &name, T &val, const T &defaultVal) const
Gets parameter of type T from the parameter server.
Definition: typedefs.hpp:247
io::CommunicationCore::connect
void connect()
Connects the data stream.
Definition: communication_core.cpp:162
RtkNtrip::keep_open
bool keep_open
Wether RTK connections shall be kept open on shutdown.
Definition: settings.hpp:72
log_level::WARN
@ WARN
Definition: typedefs.hpp:174
param
T param(const std::string &param_name, const T &default_val)
RtkIpServer
Definition: settings.hpp:75
QuaternionMsg
geometry_msgs::Quaternion QuaternionMsg
Definition: typedefs.hpp:99
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
RtkIpServer::id
std::string id
The IP server id.
Definition: settings.hpp:78
tf2::TransformException
rosaic_node::ROSaicNode::tfBuffer_
tf2_ros::Buffer tfBuffer_
tf2 buffer and listener
Definition: rosaic_node.hpp:132
RtkNtrip::mountpoint
std::string mountpoint
Mountpoint for NTRIP service.
Definition: settings.hpp:60
ros::Duration
RtkNtrip::password
std::string password
Password for NTRIP service.
Definition: settings.hpp:58
log_level::FATAL
@ FATAL
Definition: typedefs.hpp:176
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