communication_core.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 #include <chrono>
32 #include <linux/serial.h>
33 
34 // Boost includes
35 #include <boost/regex.hpp>
38 
39 #ifndef ANGLE_MAX
40 #define ANGLE_MAX 180
41 #endif
42 
43 #ifndef ANGLE_MIN
44 #define ANGLE_MIN -180
45 #endif
46 
47 #ifndef THETA_Y_MAX
48 #define THETA_Y_MAX 90
49 #endif
50 
51 #ifndef THETA_Y_MIN
52 #define THETA_Y_MIN -90
53 #endif
54 
55 #ifndef LEVER_ARM_MAX
56 #define LEVER_ARM_MAX 100
57 #endif
58 
59 #ifndef LEVER_ARM_MIN
60 #define LEVER_ARM_MIN -100
61 #endif
62 
63 #ifndef HEADING_MAX
64 #define HEADING_MAX 360
65 #endif
66 
67 #ifndef HEADING_MIN
68 #define HEADING_MIN -360
69 #endif
70 
71 #ifndef PITCH_MAX
72 #define PITCH_MAX 90
73 #endif
74 
75 #ifndef PITCH_MIN
76 #define PITCH_MIN -90
77 #endif
78 
79 #ifndef ATTSTD_DEV_MIN
80 #define ATTSTD_DEV_MIN 0
81 #endif
82 
83 #ifndef ATTSTD_DEV_MAX
84 #define ATTSTD_DEV_MAX 5
85 #endif
86 
87 #ifndef POSSTD_DEV_MIN
88 #define POSSTD_DEV_MIN 0
89 #endif
90 
91 #ifndef POSSTD_DEV_MAX
92 #define POSSTD_DEV_MAX 100
93 #endif
94 
101 boost::mutex g_response_mutex;
106 boost::condition_variable g_response_condition;
108 boost::mutex g_cd_mutex;
112 boost::condition_variable g_cd_condition;
117 std::string g_rx_tcp_port;
120 uint32_t g_cd_count;
121 
123  node_(node), handlers_(node, settings), settings_(settings), stopping_(false)
124 {
125  g_response_received = false;
126  g_cd_received = false;
127  g_read_cd = true;
128  g_cd_count = 0;
129 }
130 
132 {
134  {
135  std::string cmd("\x0DSSSSSSSSSSSSSSSSSSS\x0D\x0D");
136  manager_.get()->send(cmd);
137  send("sdio, " + mainPort_ + ", auto, none\x0D");
138  for (auto ntrip : settings_->rtk_settings.ntrip)
139  {
140  if (!ntrip.id.empty() && !ntrip.keep_open)
141  {
142  send("snts, " + ntrip.id + ", off \x0D");
143  }
144  }
145  for (auto ip_server : settings_->rtk_settings.ip_server)
146  {
147  if (!ip_server.id.empty() && !ip_server.keep_open)
148  {
149  send("sdio, " + ip_server.id + ", auto, none\x0D");
150  send("siss, " + ip_server.id + ", 0\x0D");
151  }
152  }
153  for (auto serial : settings_->rtk_settings.serial)
154  {
155  if (!serial.port.empty() && !serial.keep_open)
156  {
157  send("sdio, " + serial.port + ", auto, none\x0D");
158  if (serial.port.rfind("COM", 0) == 0)
159  send("scs, " + serial.port +
160  ", baud115200, bits8, No, bit1, none\x0D");
161  }
162  }
163  if (!settings_->ins_vsm_ip_server_id.empty())
164  {
166  {
167  send("sdio, " + settings_->ins_vsm_ip_server_id +
168  ", auto, none\x0D");
169  send("siss, " + settings_->ins_vsm_ip_server_id + ", 0\x0D");
170  }
171  }
172  if (!settings_->ins_vsm_serial_port.empty())
173  {
175  {
176  if (settings_->ins_vsm_serial_port.rfind("COM", 0) == 0)
177  send("scs, " + settings_->ins_vsm_serial_port +
178  ", baud115200, bits8, No, bit1, none\x0D");
179  send("sdio, " + settings_->ins_vsm_serial_port +
180  ", auto, none\x0D");
181  }
182  }
183 
184  send("logout \x0D");
185  }
186 
187  stopping_ = true;
188  connectionThread_->join();
189 }
190 
192 {
193  // It is imperative to hold a lock on the mutex "g_cd_mutex" while
194  // modifying the variable and "g_cd_received".
195  boost::mutex::scoped_lock lock_cd(g_cd_mutex);
196  // Escape sequence (escape from correction mode), ensuring that we can send
197  // our real commands afterwards...
198  std::string cmd("\x0DSSSSSSSSSSSSSSSSSSS\x0D\x0D");
199  manager_.get()->send(cmd);
200  // We wait for the connection descriptor before we send another command,
201  // otherwise the latter would not be processed.
202  g_cd_condition.wait(lock_cd, []() { return g_cd_received; });
203  g_cd_received = false;
204 }
205 
207 {
208  node_->log(LogLevel::DEBUG, "Called initializeIO() method");
209  boost::smatch match;
210  // In fact: smatch is a typedef of match_results<string::const_iterator>
211  if (boost::regex_match(settings_->device, match,
212  boost::regex("(tcp)://(.+):(\\d+)")))
213  // C++ needs \\d instead of \d: Both mean decimal.
214  // Note that regex_match can be used with a smatch object to store results, or
215  // without. In any case, true is returned if and only if it matches the
216  // !complete! string.
217  {
218  // The first sub_match (index 0) contained in a match_result always
219  // represents the full match within a target sequence made by a regex, and
220  // subsequent sub_matches represent sub-expression matches corresponding in
221  // sequence to the left parenthesis delimiting the sub-expression in the
222  // regex, i.e. $n Perl is equivalent to m[n] in boost regex.
223  tcp_host_ = match[2];
224  tcp_port_ = match[3];
225 
226  serial_ = false;
227  connectionThread_.reset(
228  new boost::thread(boost::bind(&Comm_IO::connect, this)));
229  } else if (boost::regex_match(settings_->device, match,
230  boost::regex("(file_name):(/|(?:/[\\w-]+)+.sbf)")))
231  {
232  serial_ = false;
234  settings_->use_gnss_time = true;
235  connectionThread_.reset(new boost::thread(
236  boost::bind(&Comm_IO::prepareSBFFileReading, this, match[2])));
237 
238  } else if (boost::regex_match(
239  settings_->device, match,
240  boost::regex("(file_name):(/|(?:/[\\w-]+)+.pcap)")))
241  {
242  serial_ = false;
243  settings_->read_from_pcap = true;
244  settings_->use_gnss_time = true;
245  connectionThread_.reset(new boost::thread(
246  boost::bind(&Comm_IO::preparePCAPFileReading, this, match[2])));
247 
248  } else if (boost::regex_match(settings_->device, match,
249  boost::regex("(serial):(.+)")))
250  {
251  serial_ = true;
252  std::string proto(match[2]);
253  std::stringstream ss;
254  ss << "Searching for serial port" << proto;
255  settings_->device = proto;
256  node_->log(LogLevel::DEBUG, ss.str());
257  connectionThread_.reset(
258  new boost::thread(boost::bind(&Comm_IO::connect, this)));
259  } else
260  {
261  std::stringstream ss;
262  ss << "Device is unsupported. Perhaps you meant 'tcp://host:port' or 'file_name:xxx.sbf' or 'serial:/path/to/device'?";
263  node_->log(LogLevel::ERROR, ss.str());
264  }
265  node_->log(LogLevel::DEBUG, "Leaving initializeIO() method");
266 }
267 
269 {
270  try
271  {
272  std::stringstream ss;
273  ss << "Setting up everything needed to read from" << file_name;
274  node_->log(LogLevel::DEBUG, ss.str());
275  initializeSBFFileReading(file_name);
276  } catch (std::runtime_error& e)
277  {
278  std::stringstream ss;
279  ss << "Comm_IO::initializeSBFFileReading() failed for SBF File" << file_name
280  << " due to: " << e.what();
281  node_->log(LogLevel::ERROR, ss.str());
282  }
283 }
284 
286 {
287  try
288  {
289  std::stringstream ss;
290  ss << "Setting up everything needed to read from " << file_name;
291  node_->log(LogLevel::DEBUG, ss.str());
292  initializePCAPFileReading(file_name);
293  } catch (std::runtime_error& e)
294  {
295  std::stringstream ss;
296  ss << "CommIO::initializePCAPFileReading() failed for SBF File " << file_name
297  << " due to: " << e.what();
298  node_->log(LogLevel::ERROR, ss.str());
299  }
300 }
301 
303 {
304  node_->log(LogLevel::DEBUG, "Called connect() method");
305  node_->log(
307  "Started timer for calling reconnect() method until connection succeeds");
308 
309  boost::asio::io_service io;
310  boost::posix_time::millisec wait_ms(
311  static_cast<uint32_t>(settings_->reconnect_delay_s * 1000));
312  while (!connected_ && !stopping_)
313  {
314  boost::asio::deadline_timer t(io, wait_ms);
315  reconnect();
316  t.wait();
317  }
318  node_->log(LogLevel::DEBUG, "Successully connected. Leaving connect() method");
319 }
320 
325 {
326  node_->log(LogLevel::DEBUG, "Called reconnect() method");
327  if (serial_)
328  {
329  bool initialize_serial_return = false;
330  try
331  {
332  node_->log(
334  "Connecting serially to device" + settings_->device +
335  ", targeted baudrate: " + std::to_string(settings_->baudrate));
336  initialize_serial_return = initializeSerial(
338  } catch (std::runtime_error& e)
339  {
340  {
341  std::stringstream ss;
342  ss << "initializeSerial() failed for device " << settings_->device
343  << " due to: " << e.what();
344  node_->log(LogLevel::ERROR, ss.str());
345  }
346  }
347  if (initialize_serial_return)
348  {
349  boost::mutex::scoped_lock lock(connection_mutex_);
350  connected_ = true;
351  lock.unlock();
352  connection_condition_.notify_one();
353  }
354  } else
355  {
356  bool initialize_tcp_return = false;
357  try
358  {
360  "Connecting to tcp://" + tcp_host_ + ":" + tcp_port_ + "...");
361  initialize_tcp_return = initializeTCP(tcp_host_, tcp_port_);
362  } catch (std::runtime_error& e)
363  {
364  {
365  std::stringstream ss;
366  ss << "initializeTCP() failed for host " << tcp_host_ << " on port "
367  << tcp_port_ << " due to: " << e.what();
368  node_->log(LogLevel::ERROR, ss.str());
369  }
370  }
371  if (initialize_tcp_return)
372  {
373  boost::mutex::scoped_lock lock(connection_mutex_);
374  connected_ = true;
375  lock.unlock();
376  connection_condition_.notify_one();
377  }
378  }
379  node_->log(LogLevel::DEBUG, "Leaving reconnect() method");
380 }
381 
390 {
391  node_->log(LogLevel::DEBUG, "Called configureRx() method");
392  {
393  // wait for connection
394  boost::mutex::scoped_lock lock(connection_mutex_);
395  connection_condition_.wait(lock, [this]() { return connected_; });
396  }
397 
398  // Determining communication mode: TCP vs USB/Serial
399  unsigned stream = 1;
400  boost::smatch match;
401  boost::regex_match(settings_->device, match,
402  boost::regex("(tcp)://(.+):(\\d+)"));
403  std::string proto(match[1]);
404  resetMainPort();
405  if (proto == "tcp")
406  {
408  } else
409  {
411  // After booting, the Rx sends the characters "x?" to all ports, which could
412  // potentially mingle with our first command. Hence send a safeguard command
413  // "lif", whose potentially false processing is harmless.
414  send("lif, Identification \x0D");
415  }
416 
417  std::string pvt_interval = parsing_utilities::convertUserPeriodToRxCommand(
419 
420  std::string rest_interval = parsing_utilities::convertUserPeriodToRxCommand(
422 
423  // Credentials for login
424  if (!settings_->login_user.empty() && !settings_->login_password.empty())
425  {
427  send("login, " + settings_->login_user + ", \"" +
428  settings_->login_password + "\" \x0D");
429  else
430  send("login, " + settings_->login_user + ", " +
431  settings_->login_password + " \x0D");
432  }
433 
434  // Turning off all current SBF/NMEA output
435  send("sso, all, none, none, off \x0D");
436  send("sno, all, none, none, off \x0D");
437 
438  // Activate NTP server
440  send("sntp, on \x0D");
441 
442  // Setting the datum to be used by the Rx (not the NMEA output though, which only
443  // provides MSL and undulation (by default with respect to WGS84), but not
444  // ellipsoidal height)
445  {
446  std::stringstream ss;
447  // WGS84 is equivalent to Default and kept for backwards compatibility
448  if (settings_->datum == "Default")
449  settings_->datum = "WGS84";
450  ss << "sgd, " << settings_->datum << "\x0D";
451  send(ss.str());
452  }
453 
454  // Setting up SBF blocks with rx_period_pvt
455  {
456  std::stringstream blocks;
458  {
459  blocks << " +ReceiverTime";
460  }
462  {
463  blocks << " +PVTCartesian";
464  }
467  (settings_->septentrio_receiver_type == "gnss")) ||
469  (settings_->septentrio_receiver_type == "gnss")) ||
471  (settings_->septentrio_receiver_type == "gnss")))
472  {
473  blocks << " +PVTGeodetic";
474  }
476  {
477  blocks << " +BaseVectorCart";
478  }
480  {
481  blocks << " +BaseVectorGeod";
482  }
484  {
485  blocks << " +PosCovCartesian";
486  }
489  (settings_->septentrio_receiver_type == "gnss")) ||
491  (settings_->septentrio_receiver_type == "gnss")) ||
493  (settings_->septentrio_receiver_type == "gnss")))
494  {
495  blocks << " +PosCovGeodetic";
496  }
499  (settings_->septentrio_receiver_type == "gnss")))
500  {
501  blocks << " +VelCovGeodetic";
502  }
505  (settings_->septentrio_receiver_type == "gnss")) ||
507  (settings_->septentrio_receiver_type == "gnss")))
508  {
509  blocks << " +AttEuler";
510  }
513  (settings_->septentrio_receiver_type == "gnss")) ||
515  (settings_->septentrio_receiver_type == "gnss")))
516  {
517  blocks << " +AttCovEuler";
518  }
520  {
521  blocks << " +MeasEpoch";
522  }
524  {
525  blocks << " +ChannelStatus +DOP";
526  }
527  // Setting SBF output of Rx depending on the receiver type
528  // If INS then...
529  if (settings_->septentrio_receiver_type == "ins")
530  {
532  {
533  blocks << " +INSNavCart";
534  }
539  {
540  blocks << " +INSNavGeod";
541  }
543  {
544  blocks << " +ExtEventINSNavGeod";
545  }
547  {
548  blocks << " +ExtEventINSNavCart";
549  }
551  {
552  blocks << " +ExtSensorMeas";
553  }
554  }
555  std::stringstream ss;
556  ss << "sso, Stream" << std::to_string(stream) << ", " << mainPort_ << ","
557  << blocks.str() << ", " << pvt_interval << "\x0D";
558  send(ss.str());
559  ++stream;
560  }
561  // Setting up SBF blocks with rx_period_rest
562  {
563  std::stringstream blocks;
564  if (settings_->septentrio_receiver_type == "ins")
565  {
567  {
568  blocks << " +IMUSetup";
569  }
571  {
572  blocks << " +VelSensorSetup";
573  }
574  }
576  {
577  blocks << " +ReceiverStatus +QualityInd";
578  }
579 
580  blocks << " +ReceiverSetup";
581 
582  std::stringstream ss;
583  ss << "sso, Stream" << std::to_string(stream) << ", " << mainPort_ << ","
584  << blocks.str() << ", " << rest_interval << "\x0D";
585  send(ss.str());
586  ++stream;
587  }
588 
589  // Setting up NMEA streams
590  {
591  send("snti, GP\x0D");
592 
593  std::stringstream blocks;
595  {
596  blocks << " +GGA";
597  }
599  {
600  blocks << " +RMC";
601  }
603  {
604  blocks << " +GSA";
605  }
607  {
608  blocks << " +GSV";
609  }
610 
611  std::stringstream ss;
612  ss << "sno, Stream" << std::to_string(stream) << ", " << mainPort_ << ","
613  << blocks.str() << ", " << pvt_interval << "\x0D";
614  send(ss.str());
615  ++stream;
616  }
617 
618  if ((settings_->septentrio_receiver_type == "ins") ||
620  {
621  {
622  std::stringstream ss;
623  ss << "sat, Main, \"" << settings_->ant_type << "\""
624  << "\x0D";
625  send(ss.str());
626  }
627 
628  // Configure Aux1 antenna
629  {
630  std::stringstream ss;
631  ss << "sat, Aux1, \"" << settings_->ant_type << "\""
632  << "\x0D";
633  send(ss.str());
634  }
635  } else if (settings_->septentrio_receiver_type == "gnss")
636  {
637  // Setting the marker-to-ARP offsets. This comes after the "sso, ...,
638  // ReceiverSetup, ..." command, since the latter is only generated when a
639  // user-command is entered to change one or more values in the block.
640  {
641  std::stringstream ss;
642  ss << "sao, Main, "
646  << settings_->ant_type << "\", " << settings_->ant_serial_nr
647  << "\x0D";
648  send(ss.str());
649  }
650 
651  // Configure Aux1 antenna
652  {
653  std::stringstream ss;
654  ss << "sao, Aux1, " << string_utilities::trimDecimalPlaces(0.0) << ", "
656  << string_utilities::trimDecimalPlaces(0.0) << ", \""
658  << "\x0D";
659  send(ss.str());
660  }
661  }
662 
663  // Configuring the corrections connection
664  for (auto ntrip : settings_->rtk_settings.ntrip)
665  {
666  if (!ntrip.id.empty())
667  {
668  // First disable any existing NTRIP connection on NTR1
669  send("snts, " + ntrip.id + ", off \x0D");
670  {
671  std::stringstream ss;
672  ss << "snts, " << ntrip.id << ", Client, " << ntrip.caster << ", "
673  << std::to_string(ntrip.caster_port) << ", " << ntrip.username
674  << ", " << ntrip.password << ", " << ntrip.mountpoint << ", "
675  << ntrip.version << ", " << ntrip.send_gga << " \x0D";
676  send(ss.str());
677  }
678  if (ntrip.tls)
679  {
680  std::stringstream ss;
681  ss << "sntt, " << ntrip.id << ", on, \"" << ntrip.fingerprint
682  << "\" \x0D";
683  send(ss.str());
684  } else
685  {
686  std::stringstream ss;
687  ss << "sntt, " << ntrip.id << ", off \x0D";
688  send(ss.str());
689  }
690  }
691  }
692 
693  for (auto ip_server : settings_->rtk_settings.ip_server)
694  {
695  if (!ip_server.id.empty())
696  // Since the Rx does not have internet (and you will not
697  // be able to share it via USB), we need to forward the
698  // corrections ourselves, though not on the same port.
699  {
700  {
701  std::stringstream ss;
702  // In case this IP server was used before, old configuration is lost
703  // of course.
704  ss << "siss, " << ip_server.id << ", "
705  << std::to_string(ip_server.port) << ", TCP2Way \x0D";
706  send(ss.str());
707  }
708  {
709  std::stringstream ss;
710  ss << "sdio, " << ip_server.id << ", " << ip_server.rtk_standard
711  << ", +SBF+NMEA \x0D";
712  send(ss.str());
713  }
714  if (ip_server.send_gga != "off")
715  {
716  std::string rate = ip_server.send_gga;
717  if (ip_server.send_gga == "auto")
718  rate = "sec1";
719  std::stringstream ss;
720  ss << "sno, Stream" << std::to_string(stream) << ", " << ip_server.id
721  << ", GGA, " << rate << " \x0D";
722  ++stream;
723  send(ss.str());
724  }
725  }
726  }
727 
728  for (auto serial : settings_->rtk_settings.serial)
729  {
730  if (!serial.port.empty())
731  {
732  if (serial.port.rfind("COM", 0) == 0)
733  send("scs, " + serial.port + ", baud" +
734  std::to_string(serial.baud_rate) +
735  ", bits8, No, bit1, none\x0D");
736 
737  std::stringstream ss;
738  ss << "sdio, " << serial.port << ", " << serial.rtk_standard
739  << ", +SBF+NMEA \x0D";
740  send(ss.str());
741  if (serial.send_gga != "off")
742  {
743  std::string rate = serial.send_gga;
744  if (serial.send_gga == "auto")
745  rate = "sec1";
746  std::stringstream ss;
747  ss << "sno, Stream" << std::to_string(stream) << ", " << serial.port
748  << ", GGA, " << rate << " \x0D";
749  ++stream;
750  send(ss.str());
751  }
752  }
753  }
754 
755  // Setting multi antenna
757  {
758  send("sga, MultiAntenna \x0D");
759  } else
760  {
761  send("sga, none \x0D");
762  }
763 
764  // Setting the Attitude Determination
765  {
770  {
771  std::stringstream ss;
772  ss << "sto, "
774  << ", "
776  << " \x0D";
777  send(ss.str());
778  } else
779  {
781  "Please specify a valid parameter for heading and pitch");
782  }
783  }
784 
785  // Setting the INS-related commands
786  if (settings_->septentrio_receiver_type == "ins")
787  {
788  // IMU orientation
789  {
790  std::stringstream ss;
795  {
796  ss << " sio, "
797  << "manual"
801  << " \x0D";
802  send(ss.str());
803  } else
804  {
805  node_->log(
807  "Please specify a correct value for IMU orientation angles");
808  }
809  }
810 
811  // Setting the INS antenna lever arm offset
812  {
819  {
820  std::stringstream ss;
821  ss << "sial, "
823  << ", "
825  << ", "
827  << " \x0D";
828  send(ss.str());
829  } else
830  {
831  node_->log(
833  "Please specify a correct value for x, y and z in the config file under ant_lever_arm");
834  }
835  }
836 
837  // Setting the user defined point offset
838  {
839  if (settings_->poi_x >= LEVER_ARM_MIN &&
845  {
846  std::stringstream ss;
847  ss << "sipl, POI1, "
851  << " \x0D";
852  send(ss.str());
853  } else
854  {
855  node_->log(
857  "Please specify a correct value for poi_x, poi_y and poi_z in the config file under poi_lever_arm");
858  }
859  }
860 
861  // Setting the Velocity sensor lever arm offset
862  {
863  if (settings_->vsm_x >= LEVER_ARM_MIN &&
869  {
870  std::stringstream ss;
871  ss << "sivl, VSM1, "
875  << " \x0D";
876  send(ss.str());
877  } else
878  {
879  node_->log(
881  "Please specify a correct value for vsm_x, vsm_y and vsm_z in the config file under vsm_lever_arm");
882  }
883  }
884 
885  // Setting the INS Solution Reference Point: MainAnt or POI1
886  // First disable any existing INS sub-block connection
887  {
888  std::stringstream ss;
889  ss << "sinc, off, all, MainAnt \x0D";
890  send(ss.str());
891  }
892 
893  // INS solution reference point
894  {
895  std::stringstream ss;
896  if (settings_->ins_use_poi)
897  {
898  ss << "sinc, on, all, "
899  << "POI1"
900  << " \x0D";
901  send(ss.str());
902  } else
903  {
904  ss << "sinc, on, all, "
905  << "MainAnt"
906  << " \x0D";
907  send(ss.str());
908  }
909  }
910 
911  // Setting the INS heading
912  {
913  std::stringstream ss;
914  if (settings_->ins_initial_heading == "auto")
915  {
916  ss << "siih, " << settings_->ins_initial_heading << " \x0D";
917  send(ss.str());
918  } else if (settings_->ins_initial_heading == "stored")
919  {
920  ss << "siih, " << settings_->ins_initial_heading << " \x0D";
921  send(ss.str());
922  } else
923  {
925  "Invalid mode specified for ins_initial_heading.");
926  }
927  }
928 
929  // Setting the INS navigation filter
930  {
935  {
936  std::stringstream ss;
937  ss << "sism, "
939  << ", "
941  << " \x0D";
942  send(ss.str());
943  } else
944  {
946  "Please specify a valid AttStsDev and PosStdDev");
947  }
948  }
949  }
950 
951  if (settings_->septentrio_receiver_type == "ins")
952  {
953  if (!settings_->ins_vsm_ip_server_id.empty())
954  {
955  send("siss, " + settings_->ins_vsm_ip_server_id + ", " +
956  std::to_string(settings_->ins_vsm_ip_server_port) +
957  ", TCP2Way \x0D");
958  send("sdio, IPS2, NMEA, none\x0D");
959  }
960  if (!settings_->ins_vsm_serial_port.empty())
961  {
962  if (settings_->ins_vsm_serial_port.rfind("COM", 0) == 0)
963  send("scs, " + settings_->ins_vsm_serial_port + ", baud" +
964  std::to_string(settings_->ins_vsm_serial_baud_rate) +
965  ", bits8, No, bit1, none\x0D");
966  send("sdio, " + settings_->ins_vsm_serial_port + ", NMEA\x0D");
967  }
968  if ((settings_->ins_vsm_ros_source == "odometry") ||
969  (settings_->ins_vsm_ros_source == "twist"))
970  {
971  std::string s;
972  s = "sdio, " + mainPort_ + ", NMEA, +NMEA +SBF\x0D";
973  send(s);
974  nmeaActivated_ = true;
975  }
976  }
977  node_->log(LogLevel::DEBUG, "Leaving configureRx() method");
978 }
979 
986 {
987  node_->log(LogLevel::DEBUG, "Called defineMessages() method");
988 
990  {
992  }
994  {
996  }
998  {
1000  }
1001  if (settings_->publish_gpgsa)
1002  {
1004  }
1005  if (settings_->publish_gpgsv)
1006  {
1011  }
1013  {
1015  }
1018  (settings_->septentrio_receiver_type == "gnss")) ||
1020  (settings_->septentrio_receiver_type == "gnss")) ||
1022  {
1024  }
1026  {
1028  }
1030  {
1032  }
1034  {
1036  }
1039  (settings_->septentrio_receiver_type == "gnss")) ||
1041  (settings_->septentrio_receiver_type == "gnss")) ||
1043  {
1045  }
1048  (settings_->septentrio_receiver_type == "gnss")))
1049  {
1051  }
1052  if (settings_->publish_atteuler ||
1054  (settings_->septentrio_receiver_type == "gnss")) ||
1056  {
1058  }
1061  (settings_->septentrio_receiver_type == "gnss")) ||
1063  {
1065  }
1067  {
1069  handlers_.insert<int32_t>("4027"); // MeasEpoch block
1070  }
1071 
1072  // INS-related SBF blocks
1074  {
1076  }
1079  (settings_->septentrio_receiver_type == "ins")) ||
1081  (settings_->septentrio_receiver_type == "ins")) ||
1082  (settings_->publish_pose &&
1083  (settings_->septentrio_receiver_type == "ins")) ||
1086  (settings_->septentrio_receiver_type == "ins")) ||
1088  (settings_->septentrio_receiver_type == "ins")) ||
1090  {
1092  }
1094  {
1096  }
1098  {
1100  }
1102  {
1104  }
1106  {
1108  }
1110  {
1112  }
1113  if (settings_->publish_gpst)
1114  {
1115  handlers_.callbackmap_ = handlers_.insert<int32_t>("GPST");
1116  }
1117  if (settings_->septentrio_receiver_type == "gnss")
1118  {
1120  {
1122  }
1123  }
1124  if (settings_->septentrio_receiver_type == "ins")
1125  {
1127  {
1128  handlers_.callbackmap_ = handlers_.insert<NavSatFixMsg>("INSNavSatFix");
1129  }
1130  }
1131  if (settings_->septentrio_receiver_type == "gnss")
1132  {
1134  {
1136  // The following blocks are never published, yet are needed for the
1137  // construction of the GPSFix message, hence we have empty callbacks.
1139  handlers_.insert<int32_t>("4013"); // ChannelStatus block
1140  handlers_.callbackmap_ = handlers_.insert<int32_t>("4001"); // DOP block
1141  }
1142  }
1143  if (settings_->septentrio_receiver_type == "ins")
1144  {
1146  {
1149  handlers_.insert<int32_t>("4013"); // ChannelStatus block
1150  handlers_.callbackmap_ = handlers_.insert<int32_t>("4001"); // DOP block
1151  }
1152  }
1153  if (settings_->septentrio_receiver_type == "gnss")
1154  {
1155  if (settings_->publish_pose)
1156  {
1158  "PoseWithCovarianceStamped");
1159  }
1160  }
1161  if (settings_->septentrio_receiver_type == "ins")
1162  {
1163  if (settings_->publish_pose)
1164  {
1166  "INSPoseWithCovarianceStamped");
1167  }
1168  }
1170  {
1172  handlers_.insert<DiagnosticArrayMsg>("DiagnosticArray");
1174  handlers_.insert<int32_t>("4014"); // ReceiverStatus block
1176  handlers_.insert<int32_t>("4082"); // QualityInd block
1177  }
1178  if (settings_->septentrio_receiver_type == "ins")
1179  {
1181  {
1183  handlers_.insert<LocalizationUtmMsg>("Localization");
1184  }
1185  }
1187  handlers_.insert<int32_t>("5902"); // ReceiverSetup block
1188  // so on and so forth...
1189  node_->log(LogLevel::DEBUG, "Leaving defineMessages() method");
1190 }
1191 
1192 void io_comm_rx::Comm_IO::send(const std::string& cmd)
1193 {
1194  // It is imperative to hold a lock on the mutex "g_response_mutex" while
1195  // modifying the variable "g_response_received".
1196  boost::mutex::scoped_lock lock(g_response_mutex);
1197  // Determine byte size of cmd and hand over to send() method of manager_
1198  manager_.get()->send(cmd);
1199  g_response_condition.wait(lock, []() { return g_response_received; });
1200  g_response_received = false;
1201 }
1202 
1203 void io_comm_rx::Comm_IO::sendVelocity(const std::string& velNmea)
1204 {
1205  if (nmeaActivated_)
1206  manager_.get()->send(velNmea);
1207 }
1208 
1209 bool io_comm_rx::Comm_IO::initializeTCP(std::string host, std::string port)
1210 {
1211  node_->log(LogLevel::DEBUG, "Calling initializeTCP() method..");
1212  host_ = host;
1213  port_ = port;
1214  // The io_context, of which io_service is a typedef of; it represents your
1215  // program's link to the operating system's I/O services.
1217  new boost::asio::io_service);
1218  boost::asio::ip::tcp::resolver::iterator endpoint;
1219 
1220  try
1221  {
1222  boost::asio::ip::tcp::resolver resolver(*io_service);
1223  // Note that tcp::resolver::query takes the host to resolve or the IP as the
1224  // first parameter and the name of the service (as defined e.g. in
1225  // /etc/services on Unix hosts) as second parameter. For the latter, one can
1226  // also use a numeric service identifier (aka port number). In any case, it
1227  // returns a list of possible endpoints, as there might be several entries
1228  // for a single host.
1229  endpoint = resolver.resolve(boost::asio::ip::tcp::resolver::query(
1230  host, port)); // Resolves query object..
1231  } catch (std::runtime_error& e)
1232  {
1233  throw std::runtime_error("Could not resolve " + host + " on port " + port +
1234  ": " + e.what());
1235  return false;
1236  }
1237 
1239  new boost::asio::ip::tcp::socket(*io_service));
1240 
1241  try
1242  {
1243  // The list of endpoints obtained above may contain both IPv4 and IPv6
1244  // endpoints, so we need to try each of them until we find one that works.
1245  // This keeps the client program independent of a specific IP version. The
1246  // boost::asio::connect() function does this for us automatically.
1247  socket->connect(*endpoint);
1248  socket->set_option(boost::asio::ip::tcp::no_delay(true));
1249  } catch (std::runtime_error& e)
1250  {
1251  throw std::runtime_error("Could not connect to " + endpoint->host_name() +
1252  ": " + endpoint->service_name() + ": " + e.what());
1253  return false;
1254  }
1255 
1256  node_->log(LogLevel::INFO, "Connected to " + endpoint->host_name() + ":" +
1257  endpoint->service_name() + ".");
1258 
1259  if (manager_)
1260  {
1261  node_->log(
1263  "You have called the InitializeTCP() method though an AsyncManager object is already available! Start all anew..");
1264  return false;
1265  }
1267  new AsyncManager<boost::asio::ip::tcp::socket>(node_, socket, io_service)));
1268  node_->log(LogLevel::DEBUG, "Leaving initializeTCP() method..");
1269  return true;
1270 }
1271 
1273 {
1274  node_->log(LogLevel::DEBUG, "Calling initializeSBFFileReading() method..");
1275  std::size_t buffer_size = 8192;
1276  uint8_t* to_be_parsed;
1277  to_be_parsed = new uint8_t[buffer_size];
1278  std::ifstream bin_file(file_name, std::ios::binary);
1279  std::vector<uint8_t> vec_buf;
1280  if (bin_file.good())
1281  {
1282  /* Reads binary data using streambuffer iterators.
1283  Copies all SBF file content into bin_data. */
1284  std::vector<uint8_t> v_buf((std::istreambuf_iterator<char>(bin_file)),
1285  (std::istreambuf_iterator<char>()));
1286  vec_buf = v_buf;
1287  bin_file.close();
1288  } else
1289  {
1290  throw std::runtime_error("I could not find your file. Or it is corrupted.");
1291  }
1292  // The spec now guarantees that vectors store their elements contiguously.
1293  to_be_parsed = vec_buf.data();
1294  std::stringstream ss;
1295  ss << "Opened and copied over from " << file_name;
1296  node_->log(LogLevel::DEBUG, ss.str());
1297 
1298  while (!stopping_) // Loop will stop if we are done reading the SBF file
1299  {
1300  try
1301  {
1302  node_->log(
1304  "Calling read_callback_() method, with number of bytes to be parsed being " +
1305  buffer_size);
1306  handlers_.readCallback(node_->getTime(), to_be_parsed, buffer_size);
1307  } catch (std::size_t& parsing_failed_here)
1308  {
1309  if (to_be_parsed - vec_buf.data() >= vec_buf.size() * sizeof(uint8_t))
1310  {
1311  break;
1312  }
1313  to_be_parsed = to_be_parsed + parsing_failed_here;
1315  "Parsing_failed_here is " + parsing_failed_here);
1316  continue;
1317  }
1318  if (to_be_parsed - vec_buf.data() >= vec_buf.size() * sizeof(uint8_t))
1319  {
1320  break;
1321  }
1322  to_be_parsed = to_be_parsed + buffer_size;
1323  }
1324  node_->log(LogLevel::DEBUG, "Leaving initializeSBFFileReading() method..");
1325 }
1326 
1328 {
1329  node_->log(LogLevel::DEBUG, "Calling initializePCAPFileReading() method..");
1330  pcapReader::buffer_t vec_buf;
1331  pcapReader::PcapDevice device(node_, vec_buf);
1332 
1333  if (!device.connect(file_name.c_str()))
1334  {
1335  node_->log(LogLevel::ERROR, "Unable to find file or either it is corrupted");
1336  return;
1337  }
1338 
1339  node_->log(LogLevel::INFO, "Reading ...");
1340  while (device.isConnected() && device.read() == pcapReader::READ_SUCCESS)
1341  ;
1342  device.disconnect();
1343 
1344  std::size_t buffer_size = pcapReader::PcapDevice::BUFFSIZE;
1345  uint8_t* to_be_parsed = new uint8_t[buffer_size];
1346  to_be_parsed = vec_buf.data();
1347 
1348  while (!stopping_) // Loop will stop if we are done reading the SBF file
1349  {
1350  try
1351  {
1352  node_->log(
1354  "Calling read_callback_() method, with number of bytes to be parsed being " +
1355  buffer_size);
1356  handlers_.readCallback(node_->getTime(), to_be_parsed, buffer_size);
1357  } catch (std::size_t& parsing_failed_here)
1358  {
1359  if (to_be_parsed - vec_buf.data() >= vec_buf.size() * sizeof(uint8_t))
1360  {
1361  break;
1362  }
1363  if (!parsing_failed_here)
1364  parsing_failed_here = 1;
1365 
1366  to_be_parsed = to_be_parsed + parsing_failed_here;
1368  "Parsing_failed_here is " + parsing_failed_here);
1369  continue;
1370  }
1371  if (to_be_parsed - vec_buf.data() >= vec_buf.size() * sizeof(uint8_t))
1372  {
1373  break;
1374  }
1375  to_be_parsed = to_be_parsed + buffer_size;
1376  }
1377  node_->log(LogLevel::DEBUG, "Leaving initializePCAPFileReading() method..");
1378 }
1379 
1380 bool io_comm_rx::Comm_IO::initializeSerial(std::string port, uint32_t baudrate,
1381  std::string flowcontrol)
1382 {
1383  node_->log(LogLevel::DEBUG, "Calling initializeSerial() method..");
1384  serial_port_ = port;
1385  baudrate_ = baudrate;
1386  // The io_context, of which io_service is a typedef of; it represents your
1387  // program's link to the operating system's I/O services.
1389  new boost::asio::io_service);
1390  // To perform I/O operations the program needs an I/O object, here "serial".
1392  new boost::asio::serial_port(*io_service));
1393 
1394  // We attempt the opening of the serial port..
1395  try
1396  {
1397  serial->open(serial_port_);
1398  } catch (std::runtime_error& e)
1399  {
1400  // and return an error message in case it fails.
1401  throw std::runtime_error("Could not open serial port : " + serial_port_ +
1402  ": " + e.what());
1403  return false;
1404  }
1405 
1406  node_->log(LogLevel::INFO, "Opened serial port " + serial_port_);
1408  "Our boost version is " + std::to_string(BOOST_VERSION) + ".");
1409  if (BOOST_VERSION < 106600) // E.g. for ROS melodic (i.e. Ubuntu 18.04), the
1410  // version is 106501, standing for 1.65.1.
1411  {
1412  // Workaround to set some options for the port manually,
1413  // cf. https://github.com/mavlink/mavros/pull/971/files
1414  // This function native_handle() may be used to obtain
1415  // the underlying representation of the serial port.
1416  // Conversion from type native_handle_type to int is done implicitly.
1417  int fd = serial->native_handle();
1418  termios tio;
1419  // Get terminal attribute, follows the syntax
1420  // int tcgetattr(int fd, struct termios *termios_p);
1421  tcgetattr(fd, &tio);
1422 
1423  // Hardware flow control settings_->.
1424  if (flowcontrol == "RTS|CTS")
1425  {
1426  tio.c_iflag &= ~(IXOFF | IXON);
1427  tio.c_cflag |= CRTSCTS;
1428  } else
1429  {
1430  tio.c_iflag &= ~(IXOFF | IXON);
1431  tio.c_cflag &= ~CRTSCTS;
1432  }
1433  // Setting serial port to "raw" mode to prevent EOF exit..
1434  cfmakeraw(&tio);
1435 
1436  // Commit settings, syntax is
1437  // int tcsetattr(int fd, int optional_actions, const struct termios
1438  // *termios_p);
1439  tcsetattr(fd, TCSANOW, &tio);
1440 
1441  // Set low latency
1442  struct serial_struct serialInfo;
1443 
1444  ioctl(fd, TIOCGSERIAL, &serialInfo);
1445  serialInfo.flags |= ASYNC_LOW_LATENCY;
1446  ioctl(fd, TIOCSSERIAL, &serialInfo);
1447  }
1448 
1449  // Set the I/O manager
1450  if (manager_)
1451  {
1452  node_->log(
1454  "You have called the initializeSerial() method though an AsyncManager object is already available! Start all anew..");
1455  return false;
1456  }
1457  node_->log(LogLevel::DEBUG, "Creating new Async-Manager object..");
1459  new AsyncManager<boost::asio::serial_port>(node_, serial, io_service)));
1460 
1461  // Setting the baudrate, incrementally..
1463  "Gradually increasing the baudrate to the desired value...");
1464  boost::asio::serial_port_base::baud_rate current_baudrate;
1465  node_->log(LogLevel::DEBUG, "Initiated current_baudrate object...");
1466  try
1467  {
1468  serial->get_option(
1469  current_baudrate); // Note that this sets current_baudrate.value() often
1470  // to 115200, since by default, all Rx COM ports,
1471  // at least for mosaic Rxs, are set to a baudrate of 115200 baud, using 8
1472  // data-bits, no parity and 1 stop-bit.
1473  } catch (boost::system::system_error& e)
1474  {
1475 
1477  "get_option failed due to " + std::string(e.what()));
1478  node_->log(LogLevel::INFO, "Additional info about error is " +
1479  boost::diagnostic_information(e));
1480  /*
1481  boost::system::error_code e_loop;
1482  do // Caution: Might cause infinite loop..
1483  {
1484  serial->get_option(current_baudrate, e_loop);
1485  } while(e_loop);
1486  */
1487  return false;
1488  }
1489  // Gradually increase the baudrate to the desired value
1490  // The desired baudrate can be lower or larger than the
1491  // current baudrate; the for loop takes care of both scenarios.
1493  "Current baudrate is " + std::to_string(current_baudrate.value()));
1494  for (uint8_t i = 0; i < sizeof(BAUDRATES) / sizeof(BAUDRATES[0]); i++)
1495  {
1496  if (current_baudrate.value() == baudrate_)
1497  {
1498  break; // Break if the desired baudrate has been reached.
1499  }
1500  if (current_baudrate.value() >= BAUDRATES[i] && baudrate_ > BAUDRATES[i])
1501  {
1502  continue;
1503  }
1504  // Increment until Baudrate[i] matches current_baudrate.
1505  try
1506  {
1507  serial->set_option(
1508  boost::asio::serial_port_base::baud_rate(BAUDRATES[i]));
1509  } catch (boost::system::system_error& e)
1510  {
1511 
1513  "set_option failed due to " + std::string(e.what()));
1514  node_->log(LogLevel::INFO, "Additional info about error is " +
1515  boost::diagnostic_information(e));
1516  return false;
1517  }
1518  usleep(SET_BAUDRATE_SLEEP_);
1519  // boost::this_thread::sleep(boost::posix_time::milliseconds(SET_BAUDRATE_SLEEP_*1000));
1520  // Boost's sleep would yield an error message with exit code -7 the second
1521  // time it is called, hence we use sleep() or usleep().
1522  try
1523  {
1524  serial->get_option(current_baudrate);
1525  } catch (boost::system::system_error& e)
1526  {
1527 
1529  "get_option failed due to " + std::string(e.what()));
1530  node_->log(LogLevel::INFO, "Additional info about error is " +
1531  boost::diagnostic_information(e));
1532  /*
1533  boost::system::error_code e_loop;
1534  do // Caution: Might cause infinite loop..
1535  {
1536  serial->get_option(current_baudrate, e_loop);
1537  } while(e_loop);
1538  */
1539  return false;
1540  }
1541  node_->log(LogLevel::DEBUG, "Set ASIO baudrate to " +
1542  std::to_string(current_baudrate.value()));
1543  }
1544  node_->log(LogLevel::INFO, "Set ASIO baudrate to " +
1545  std::to_string(current_baudrate.value()) +
1546  ", leaving InitializeSerial() method");
1547  return true;
1548 }
1549 
1551 {
1552  namespace bp = boost::placeholders;
1553 
1554  node_->log(LogLevel::DEBUG, "Called setManager() method");
1555  if (manager_)
1556  return;
1557  manager_ = manager;
1558  manager_->setCallback(boost::bind(&CallbackHandlers::readCallback, &handlers_,
1559  bp::_1, bp::_2, bp::_3));
1560  node_->log(LogLevel::DEBUG, "Leaving setManager() method");
1561 }
double theta_z
IMU orientation z-angle.
Definition: settings.h:152
septentrio_gnss_driver::VelCovGeodetic VelCovGeodeticMsg
Definition: typedefs.hpp:124
bool connected_
Whether connecting to Rx was successful.
nmea_msgs::Gpgsa GpgsaMsg
Definition: typedefs.hpp:128
uint32_t polling_period_rest
Polling period for all other SBF blocks and NMEA messages.
Definition: settings.h:128
ReadResult read()
Attempt to read a packet and store data to buffer.
Definition: pcap_reader.cpp:90
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
boost::shared_ptr< Manager > manager_
septentrio_gnss_driver::AttCovEuler AttCovEulerMsg
Definition: typedefs.hpp:114
bool ins_in_gnss_mode
Handle the case when an INS is used in GNSS mode.
Definition: settings.h:259
uint32_t baudrate_
Baudrate at the moment, unless InitializeSerial or ResetSerial fail.
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
void send(const std::string &)
Hands over to the send() method of manager_.
bool read_from_sbf_log
Whether or not we are reading from an SBF file.
Definition: settings.h:282
std::string hw_flow_control
HW flow control.
Definition: settings.h:119
string cmd
void readCallback(Timestamp recvTimestamp, const uint8_t *data, std::size_t &size)
Searches for Rx messages that could potentially be decoded/parsed/published.
bool publish_poscovgeodetic
Definition: settings.h:212
#define THETA_Y_MAX
std::string ins_vsm_serial_port
VSM serial port.
Definition: settings.h:300
std::vector< uint8_t > buffer_t
Definition: pcap_reader.hpp:49
Settings * settings_
Settings.
void prepareSBFFileReading(std::string file_name)
Sets up the stage for SBF file reading.
double poi_x
INS POI offset in x-dimension.
Definition: settings.h:160
Comm_IO(ROSaicNodeBase *node, Settings *settings)
Constructor of the class Comm_IO.
void defineMessages()
Defines which Rx messages to read and which ROS messages to publish.
bool serial_
Whether yet-to-be-established connection to Rx will be serial or TCP.
XmlRpcServer s
static const unsigned int SET_BAUDRATE_SLEEP_
std::string ant_serial_nr
Serial number of your particular Main antenna.
Definition: settings.h:142
bool g_response_received
Determines whether a command reply was received from the Rx.
septentrio_gnss_driver::PVTGeodetic PVTGeodeticMsg
Definition: typedefs.hpp:117
bool containsSpace(const std::string str)
Checks if a string contains spaces.
septentrio_gnss_driver::VelSensorSetup VelSensorSetupMsg
Definition: typedefs.hpp:136
void disconnect()
Close connected file.
Definition: pcap_reader.cpp:78
bool isConnected() const
Check if file is open and healthy.
Definition: pcap_reader.cpp:88
septentrio_gnss_driver::INSNavCart INSNavCartMsg
Definition: typedefs.hpp:133
bool initializeSerial(std::string port, uint32_t baudrate=115200, std::string flowcontrol="None")
Initializes the serial port.
void initializeIO()
Initializes the I/O handling.
#define PITCH_MIN
#define HEADING_MAX
void initializeSBFFileReading(std::string file_name)
Initializes SBF file reading and reads SBF file by repeatedly calling read_callback_() ...
RtkSettings rtk_settings
RTK corrections settings.
Definition: settings.h:186
std::unique_ptr< boost::thread > connectionThread_
Connection or reading thread.
Highest-Level view on communication services.
bool ins_use_poi
INS solution reference point.
Definition: settings.h:178
void reconnect()
Attempts to (re)connect every reconnect_delay_s_ seconds.
#define THETA_Y_MIN
std::string login_user
Username for login.
Definition: settings.h:110
septentrio_gnss_driver::ExtSensorMeas ExtSensorMeasMsg
Definition: typedefs.hpp:137
std::vector< RtkNtrip > ntrip
Definition: settings.h:97
std::string ins_vsm_ros_source
VSM source for INS.
Definition: settings.h:286
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
void log(LogLevel logLevel, const std::string &s)
Log function to provide abstraction of ROS loggers.
Definition: typedefs.hpp:231
bool connect(const char *device)
Try to open a pcap file.
Definition: pcap_reader.cpp:60
std::string convertUserPeriodToRxCommand(uint32_t period_user)
Transforms the input polling period [milliseconds] into a std::string number that can be appended to ...
#define ANGLE_MIN
septentrio_gnss_driver::AttEuler AttEulerMsg
Definition: typedefs.hpp:115
geometry_msgs::TransformStamped t
septentrio_gnss_driver::IMUSetup IMUSetupMsg
Definition: typedefs.hpp:135
boost::mutex g_cd_mutex
Mutex to control changes of global variable "g_cd_received".
bool publish_twist
Whether or not to publish the TwistWithCovarianceStampedMsg message.
Definition: settings.h:249
std::string serial_port_
Saves the port description.
nmea_msgs::Gpgsv GpgsvMsg
Definition: typedefs.hpp:129
Data read successfully.
Definition: pcap_reader.hpp:55
std::string rx_serial_port
Definition: settings.h:122
nmea_msgs::Gprmc GprmcMsg
Definition: typedefs.hpp:130
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
ROSaicNodeBase * node_
Pointer to Node.
static const size_t BUFFSIZE
Definition: pcap_reader.hpp:72
double ant_lever_x
INS antenna lever arm x-offset.
Definition: settings.h:154
#define POSSTD_DEV_MAX
nmea_msgs::Gpgga GpggaMsg
Definition: typedefs.hpp:127
uint32_t polling_period_pvt
Polling period for PVT-related SBF blocks.
Definition: settings.h:126
std::string port_
Port over which TCP/IP connection is currently established.
bool publish_insnavgeod
Whether or not to publish the INSNavGeodMsg message.
Definition: settings.h:223
bool publish_gprmc
Whether or not to publish the RMC message.
Definition: settings.h:190
septentrio_gnss_driver::BaseVectorCart BaseVectorCartMsg
Definition: typedefs.hpp:108
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 initializeTCP(std::string host, std::string port)
Initializes the TCP I/O.
bool use_gnss_time
Definition: settings.h:263
void resetMainPort()
Reset main port so it can receive commands.
septentrio_gnss_driver::ReceiverTime ReceiverTimeMsg
Definition: typedefs.hpp:120
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
#define HEADING_MIN
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 trimDecimalPlaces(double num)
Trims decimal places to two.
CallbackMap insert(std::string message_key)
Adds a pair to the multimap "callbackmap_", with the message_key being the key.
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
Settings struct.
Definition: settings.h:103
bool publish_gpgga
Whether or not to publish the GGA message.
Definition: settings.h:188
boost::condition_variable g_response_condition
Condition variable complementing "g_response_mutex".
bool publish_localization
Whether or not to publish the LocalizationMsg message.
Definition: settings.h:247
septentrio_gnss_driver::INSNavGeod INSNavGeodMsg
Definition: typedefs.hpp:134
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
static const uint32_t BAUDRATES[]
Possible baudrates for the Rx.
std::string g_rx_tcp_port
Rx TCP port, e.g. IP10 or IP11, to which ROSaic is connected to.
~Comm_IO()
Default destructor of the class Comm_IO.
Class for handling a pcap file.
Definition: pcap_reader.hpp:69
bool publish_pvtcartesian
Definition: settings.h:199
uint32_t g_cd_count
#define PITCH_MAX
uint32_t baudrate
Baudrate.
Definition: settings.h:117
bool read_from_pcap
Whether or not we are reading from a PCAP file.
Definition: settings.h:284
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
void preparePCAPFileReading(std::string file_name)
Sets up the stage for PCAP file reading.
std::string device
Device port.
Definition: settings.h:108
std::string mainPort_
Communication ports.
void sendVelocity(const std::string &velNmea)
Hands over NMEA velocity message over to the send() method of manager_.
septentrio_gnss_driver::PosCovGeodetic PosCovGeodeticMsg
Definition: typedefs.hpp:119
bool publish_pvtgeodetic
Whether or not to publish the PVTGeodeticMsg message.
Definition: settings.h:201
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
septentrio_gnss_driver::PosCovCartesian PosCovCartesianMsg
Definition: typedefs.hpp:118
void configureRx()
Configures Rx: Which SBF/NMEA messages it should output and later correction settings.
bool g_cd_received
Determines whether the connection descriptor was received from the Rx.
float reconnect_delay_s
Definition: settings.h:115
std::string tcp_port_
TCP port number.
boost::condition_variable connection_condition_
bool ins_vsm_ip_server_keep_open
Wether VSM shall be kept open om shutdown.
Definition: settings.h:298
#define POSSTD_DEV_MIN
std::atomic< bool > stopping_
Indicator for threads to exit.
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
boost::condition_variable g_cd_condition
Condition variable complementing "g_cd_mutex".
diagnostic_msgs::DiagnosticArray DiagnosticArrayMsg
Definition: typedefs.hpp:93
Declares a class for handling pcap files.
float att_std_dev
Attitude deviation mask.
Definition: settings.h:182
void setManager(const boost::shared_ptr< Manager > &manager)
Set the I/O manager.
float pos_std_dev
Position deviation mask.
Definition: settings.h:184
bool g_read_cd
This is the central interface between ROSaic and the Rx(s), managing I/O operations such as reading m...
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
Timestamp getTime()
Gets current timestamp.
Definition: typedefs.hpp:259
nav_msgs::Odometry LocalizationUtmMsg
Definition: typedefs.hpp:105
CallbackHandlers handlers_
Callback handlers for the inwards streaming messages.
double vsm_z
INS velocity sensor lever arm z-offset.
Definition: settings.h:170
#define ANGLE_MAX
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
This class is the base class for abstraction.
Definition: typedefs.hpp:174
double theta_y
IMU orientation y-angle.
Definition: settings.h:150
#define ATTSTD_DEV_MIN
void initializePCAPFileReading(std::string file_name)
Initializes PCAP file reading and reads PCAP file by repeatedly calling read_callback_() ...
boost::mutex g_response_mutex
Mutex to control changes of global variable "g_response_received".
#define ATTSTD_DEV_MAX
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
std::string ins_initial_heading
For heading computation when unit is powered-cycled.
Definition: settings.h:180
septentrio_gnss_driver::PVTCartesian PVTCartesianMsg
Definition: typedefs.hpp:116
#define LEVER_ARM_MIN
void connect()
Calls the reconnect() method.
sensor_msgs::NavSatFix NavSatFixMsg
Definition: typedefs.hpp:101
septentrio_gnss_driver::BaseVectorGeod BaseVectorGeodMsg
Definition: typedefs.hpp:109
std::string tcp_host_
Host name of TCP server.
gps_common::GPSFix GPSFixMsg
Definition: typedefs.hpp:99
geometry_msgs::PoseWithCovarianceStamped PoseWithCovarianceStampedMsg
Definition: typedefs.hpp:96
bool multi_antenna
INS multiantenna.
Definition: settings.h:176
bool publish_navsatfix
Whether or not to publish the NavSatFixMsg message.
Definition: settings.h:237
#define LEVER_ARM_MAX
std::string host_
Host currently connected to.
float delta_u
Marker-to-ARP offset in the upward direction.
Definition: settings.h:134
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:55