Go to the documentation of this file.
   34 #include <linux/serial.h> 
   37 #include <boost/regex.hpp> 
   64         node_(node), settings_(node->
settings()), telegramHandler_(node),
 
   80         auto telegram = std::make_shared<Telegram>();
 
   97             send(
"sso, all, none, none, off \x0D");
 
   98             send(
"sno, all, none, none, off \x0D");
 
  105                 if (!ntrip.id.empty() && !ntrip.keep_open)
 
  107                     send(
"snts, " + ntrip.id + 
", off \x0D");
 
  112                 if (!ip_server.id.empty() && !ip_server.keep_open)
 
  114                     send(
"sdio, " + ip_server.id + 
",  auto, none\x0D");
 
  115                     send(
"siss, " + ip_server.id + 
",  0\x0D");
 
  120                 if (!serial.port.empty() && !serial.keep_open)
 
  122                     send(
"sdio, " + serial.port + 
",  auto, none\x0D");
 
  123                     if (serial.port.rfind(
"COM", 0) == 0)
 
  124                         send(
"scs, " + serial.port +
 
  125                              ", baud115200, bits8, No, bit1, none\x0D");
 
  143                              ", baud115200, bits8, No, bit1, none\x0D");
 
  151                 std::stringstream ss;
 
  152                 ss << 
"sou, off \x0D";
 
  157                     std::stringstream ss;
 
  158                     ss << 
"snc, off \x0D";
 
  173             "Started timer for calling connect() method until connection succeeds");
 
  175         boost::asio::io_context 
io;
 
  199                    "Successully connected. Leaving connect() method");
 
  276                        "Called configureRx() method but IO is not initialized.");
 
  284                            boost::regex(
"(tcp)://(.+):(\\d+)"));
 
  285         std::string proto(match[1]);
 
  295             std::string pvt_interval =
 
  299             std::string rest_interval =
 
  315             send(
"sso, all, none, none, off \x0D");
 
  316             send(
"sno, all, none, none, off \x0D");
 
  329                     while (std::getline(filestream, line))
 
  336                         std::to_string(ctr) +
 
  337                             " custom commands have been parsed and sent to the Rx.");
 
  341                                "Custom command file " +
 
  343                                    " could not be found.");
 
  350                 std::string tcp_mode;
 
  352                     tcp_mode = 
"TCP2Way";
 
  362                 std::string destination;
 
  366                     destination = 
"255.255.255.255";
 
  378                 send(
"sntp, on \x0D");
 
  382                 send(
"sptp, on \x0D");
 
  388                 std::stringstream ss;
 
  396                     std::stringstream ss;
 
  404                     std::stringstream ss;
 
  415                     std::stringstream ss;
 
  430                     std::stringstream ss;
 
  443                 if (!ntrip.id.empty())
 
  446                     send(
"snts, " + ntrip.id + 
", off \x0D");
 
  448                         std::stringstream ss;
 
  449                         ss << 
"snts, " << ntrip.id << 
", Client, " << ntrip.caster
 
  450                            << 
", " << std::to_string(ntrip.caster_port) << 
", " 
  451                            << ntrip.username << 
", " << ntrip.password << 
", " 
  452                            << ntrip.mountpoint << 
", " << ntrip.version << 
", " 
  453                            << ntrip.send_gga << 
" \x0D";
 
  458                         std::stringstream ss;
 
  459                         ss << 
"sntt, " << ntrip.id << 
", on, \"" << ntrip.fingerprint
 
  464                         std::stringstream ss;
 
  465                         ss << 
"sntt, " << ntrip.id << 
", off \x0D";
 
  473                 if (!ip_server.id.empty())
 
  476                         std::stringstream ss;
 
  479                         ss << 
"siss, " << ip_server.id << 
", " 
  480                            << std::to_string(ip_server.port) << 
", TCP2Way \x0D";
 
  484                         std::stringstream ss;
 
  485                         ss << 
"sdio, " << ip_server.id << 
", " 
  486                            << ip_server.rtk_standard << 
", +SBF+NMEA \x0D";
 
  489                     if (ip_server.send_gga != 
"off")
 
  491                         std::string rate = ip_server.send_gga;
 
  492                         if (ip_server.send_gga == 
"auto")
 
  494                         std::stringstream ss;
 
  495                         ss << 
"sno, Stream" << std::to_string(stream) << 
", " 
  496                            << ip_server.id << 
", GGA, " << rate << 
" \x0D";
 
  505                 if (!serial.port.empty())
 
  507                     if (serial.port.rfind(
"COM", 0) == 0)
 
  508                         send(
"scs, " + serial.port + 
", baud" +
 
  509                              std::to_string(serial.baud_rate) +
 
  510                              ", bits8, No, bit1, none\x0D");
 
  512                     std::stringstream ss;
 
  513                     ss << 
"sdio, " << serial.port << 
", " << serial.rtk_standard
 
  514                        << 
", +SBF+NMEA \x0D";
 
  516                     if (serial.send_gga != 
"off")
 
  518                         std::string rate = serial.send_gga;
 
  519                         if (serial.send_gga == 
"auto")
 
  521                         std::stringstream ss;
 
  522                         ss << 
"sno, Stream" << std::to_string(stream) << 
", " 
  523                            << serial.port << 
", GGA, " << rate << 
" \x0D";
 
  534                     send(
"sga, MultiAntenna \x0D");
 
  538                         "Multi antenna requested but Rx does not support it.");
 
  541                 send(
"sga, none \x0D");
 
  551                     std::stringstream ss;
 
  564                         "Please specify a valid parameter for heading and pitch");
 
  573                     std::stringstream ss;
 
  581                         ss << 
" sio, " << 
"manual" << 
", " 
  593                             "Please specify a correct value for IMU orientation angles");
 
  606                         std::stringstream ss;
 
  622                             "Please specify a correct value for x, y and z in the config file under ant_lever_arm");
 
  635                         std::stringstream ss;
 
  648                             "Please specify a correct value for poi_x, poi_y and poi_z in the config file under poi_lever_arm");
 
  661                         std::stringstream ss;
 
  674                             "Please specify a correct value for vsm_x, vsm_y and vsm_z in the config file under vsm_lever_arm");
 
  681                     std::stringstream ss;
 
  682                     ss << 
"sinc, off, all, MainAnt \x0D";
 
  688                     std::stringstream ss;
 
  691                         ss << 
"sinc, on, all, " << 
"POI1" << 
" \x0D";
 
  695                         ss << 
"sinc, on, all, " << 
"MainAnt" << 
" \x0D";
 
  702                     std::stringstream ss;
 
  715                             "Invalid mode specified for ins_initial_heading.");
 
  726                         std::stringstream ss;
 
  738                                    "Please specify a valid AttStsDev and PosStdDev");
 
  747                 std::stringstream ss;
 
  753                     std::stringstream ss;
 
  761                             "OSNMA mode set to strict but no NTP server provided. In Strict mode an NTP server is mandatory!");
 
  767                 std::stringstream blocks;
 
  772                         blocks << 
" +IMUSetup";
 
  776                         blocks << 
" +VelSensorSetup";
 
  781                     blocks << 
" +QualityInd";
 
  785                     blocks << 
" +RFStatus";
 
  791                     blocks << 
" +GALAuthStatus";
 
  794                 blocks << 
" +ReceiverSetup +ReceiverStatus";
 
  796                 std::stringstream ss;
 
  797                 ss << 
"sso, Stream" << std::to_string(stream) << 
", " << 
streamPort_ 
  798                    << 
"," << blocks.str() << 
", " << rest_interval << 
"\x0D";
 
  804             send(
"sop, \"\", \"\" \x0D");
 
  809                     send(
"snti, auto\x0D");
 
  811                     send(
"snti, GP\x0D");
 
  813                 std::stringstream blocks;
 
  831                 std::stringstream ss;
 
  832                 ss << 
"sno, Stream" << std::to_string(stream) << 
", " << 
streamPort_ 
  833                    << 
"," << blocks.str() << 
", " << pvt_interval << 
"\x0D";
 
  840                 std::stringstream blocks;
 
  843                     blocks << 
" +ReceiverTime";
 
  847                     blocks << 
" +PVTCartesian";
 
  860                     blocks << 
" +PVTGeodetic";
 
  864                     blocks << 
" +BaseVectorCart";
 
  868                     blocks << 
" +BaseVectorGeod";
 
  872                     blocks << 
" +PosCovCartesian";
 
  882                     blocks << 
" +PosCovGeodetic";
 
  886                     blocks << 
" +VelCovCartesian";
 
  892                     blocks << 
" +VelCovGeodetic";
 
  900                     blocks << 
" +AttEuler";
 
  908                     blocks << 
" +AttCovEuler";
 
  912                     blocks << 
" +MeasEpoch";
 
  916                     blocks << 
" +ChannelStatus +DOP";
 
  926                         blocks << 
" +INSNavCart";
 
  936                         blocks << 
" +INSNavGeod";
 
  940                         blocks << 
" +ExtEventINSNavGeod";
 
  944                         blocks << 
" +ExtEventINSNavCart";
 
  948                         blocks << 
" +ExtSensorMeas";
 
  951                 std::stringstream ss;
 
  952                 ss << 
"sso, Stream" << std::to_string(stream) << 
", " << 
streamPort_ 
  953                    << 
"," << blocks.str() << 
", " << pvt_interval << 
"\x0D";
 
  973                              ", bits8, No, bit1, none\x0D");
 
  983                              ", NMEA, +NMEA +SBF\x0D");
 
  996             send(
"eccf, Current, Boot\x0D");
 
 1041         std::string cmd(
"\x0DSSSSSSSSSS\x0D\x0D");
 
 1057             std::shared_ptr<Telegram> telegram;
 
  
Osnma osnma
OSNMA settings.
bool publish_pose
Whether or not to publish the PoseWithCovarianceStampedMsg message.
static const int8_t PITCH_MIN
bool publish_attcoveuler
Whether or not to publish the AttCovEulerMsg message.
void resetSettings()
Resets Rx settings.
std::string ins_initial_heading
For heading computation when unit is powered-cycled.
std::string serial_port
VSM serial port.
static const int8_t THETA_Y_MIN
std::unique_ptr< AsyncManager< TcpIo > > tcpVsm_
bool latency_compensation
Wether processing latency shall be compensated for in ROS timestamp.
bool keep_open
Wether OSNMA shall be kept open on shutdown.
bool publish_imusetup
Whether or not to publish the IMUSetupMsg message.
bool publish_twist
Whether or not to publish the TwistWithCovarianceStampedMsg message.
bool publish_localization
Whether or not to publish the LocalizationMsg message.
float pos_std_dev
Position deviation mask.
std::vector< RtkSerial > serial
void resetWaitforMainCd()
Returns the connection descriptor.
std::string login_password
Password for login.
bool ip_server_keep_open
Wether VSM shall be kept open om shutdown.
std::string ros_source
VSM source for INS.
Highest-Level view on communication services.
bool publish_pvtcartesian
std::string udp_ip_server
UDP IP server id.
std::string getMainCd()
Returns the connection descriptor.
std::string ip_server
VSM IP server id.
bool publish_pvtgeodetic
Whether or not to publish the PVTGeodeticMsg message.
double heading_offset
Attitude offset determination in longitudinal direction.
void log(log_level::LogLevel logLevel, const std::string &s) const
Log function to provide abstraction of ROS loggers.
bool publish_gpgga
Whether or not to publish the GGA message.
bool publish_imu
Whether or not to publish the ImuMsg message.
std::string ntp_server
Server for NTP synchronization.
bool multi_antenna
INS multiantenna.
double vsm_x
INS velocity sensor lever arm x-offset.
uint32_t udp_port
UDP port.
uint32_t serial_baud_rate
VSM serial baud rate.
std::string convertUserPeriodToRxCommand(uint32_t period_user)
Transforms the input polling period [milliseconds] into a std::string number that can be appended to ...
static const int16_t ANGLE_MIN
bool ntp_server
Wether NTP server shall be activated.
float delta_n
Marker-to-ARP offset in the northward direction.
uint32_t polling_period_pvt
Polling period for PVT-related SBF blocks.
std::string mode
OSNMA mode.
std::unique_ptr< AsyncManager< TcpIo > > tcpClient_
std::string datum
Datum to be used.
device_type::DeviceType device_type
Device type.
double theta_z
IMU orientation z-angle.
bool publish_gpst
Whether or not to publish the TimeReferenceMsg message with GPST.
double poi_y
INS POI offset in y-dimension.
bool publish_galauthstatus
Whether or not to publish the GALAuthStatus message and diagnostics.
static const int8_t POSSTD_DEV_MAX
bool publish_velcovcartesian
bool publish_aimplusstatus
double poi_x
INS POI offset in x-dimension.
void configureRx()
Configures Rx: Which SBF/NMEA messages it should output and later correction settings.
void sendVelocity(const std::string &velNmea)
Hands over NMEA velocity message over to the send() method of manager_.
This class is the base class for abstraction.
std::string tcp_ip_server
TCP IP server id.
void pop(T &output) noexcept
double theta_x
IMU orientation x-angle.
bool publish_velsensorsetup
Whether or not to publish the VelSensorSetupMsg message.
double theta_y
IMU orientation y-angle.
std::string ant_aux1_serial_nr
Serial number of your particular Aux1 antenna.
static const int8_t ATTSTD_DEV_MIN
bool publish_exteventinsnavcart
Whether or not to publish the ExtEventINSNavCartMsg message.
bool publish_gpsfix
Whether or not to publish the GpsFixMsg message.
std::thread processingThread_
Processing thread.
bool publish_gpgsa
Whether or not to publish the GSA message.
const Settings * settings_
Settings.
bool publish_velcovgeodetic
bool ptp_server_clock
Wether PTP grandmaster clock shall be activated.
uint32_t tcp_port
TCP port.
bool publish_poscovgeodetic
bool publish_tf_ecef
Whether or not to publish the tf of the localization.
double vsm_y
INS velocity sensor lever arm y-offset.
std::string mainConnectionPort_
Main communication port.
bool publish_basevectorcart
static const int16_t HEADING_MAX
std::vector< RtkNtrip > ntrip
bool serial_keep_open
Wether VSM shall be kept open om shutdown.
CommunicationCore(ROSaicNodeBase *node)
Constructor of the class CommunicationCore.
static const int8_t LEVER_ARM_MIN
double vsm_z
INS velocity sensor lever arm z-offset.
double pitch_offset
Attitude offset determination in latitudinal direction.
std::string trimDecimalPlaces(double num)
Trims decimal places to three.
std::string ant_aux1_type
bool publish_localization_ecef
Whether or not to publish the LocalizationMsg message.
bool isIns()
Check if Rx is INS.
float delta_u
Marker-to-ARP offset in the upward direction.
ROSaicNodeBase * node_
Pointer to Node.
bool ins_use_poi
INS solution reference point.
std::string ant_serial_nr
Serial number of your particular Main antenna.
static const int8_t PITCH_MAX
bool publish_atteuler
Whether or not to publish the AttEulerMsg message.
std::string login_user
Username for login.
static const int8_t THETA_Y_MAX
bool use_stream_device
Wether to use stream device tcp.
bool publish_basevectorgeod
Whether or not to publish the BaseVectorGeodMsg message.
bool publish_diagnostics
Whether or not to publish the DiagnosticArrayMsg message.
std::unique_ptr< UdpClient > udpClient_
void push(const T &input) noexcept
uint32_t polling_period_rest
Polling period for all other SBF blocks and NMEA messages.
std::vector< RtkIpServer > ip_server
bool hasHeading()
Check if Rx has heading.
double poi_z
INS POI offset in z-dimension.
static const int16_t ANGLE_MAX
std::string custom_commands_file
Custom commands file.
bool publish_poscovcartesian
bool publish_insnavcart
Whether or not to publish the INSNavCartMsg message.
float delta_e
Marker-to-ARP offset in the eastward direction.
bool initializeIo()
Initializes the I/O handling.
bool read_from_sbf_log
Whether or not we are reading from an SBF file.
bool containsSpace(const std::string str)
Checks if a string contains spaces.
InsVsm ins_vsm
INS VSM setting.
double ant_lever_z
INS antenna lever arm z-offset.
bool publish_gprmc
Whether or not to publish the RMC message.
void send(const std::string &cmd)
Hands over to the send() method of manager_.
void connect()
Connects the data stream.
void waitForCapabilities()
Waits for capabilities.
TelegramQueue telegramQueue_
TelegramQueue.
bool publish_navsatfix
Whether or not to publish the NavSatFixMsg message.
bool publish_tf
Whether or not to publish the tf of the localization.
std::string udp_unicast_ip
UDP unicast destination ip.
static const int8_t POSSTD_DEV_MIN
float att_std_dev
Attitude deviation mask.
std::atomic< bool > running_
Indicator for threads to run.
bool publish_measepoch
Whether or not to publish the MeasEpoch message.
bool publish_exteventinsnavgeod
Whether or not to publish the ExtEventINSNavGeodMsg message.
static const int8_t ATTSTD_DEV_MAX
double ant_lever_x
INS antenna lever arm x-offset.
bool publish_extsensormeas
Whether or not to publish the ExtSensorMeasMsg message.
void waitForResponse()
Waits for response.
std::string resetMainConnection()
Reset main connection so it can receive commands.
std::string device
Device.
~CommunicationCore()
Default destructor of the class CommunicationCore.
static const int16_t HEADING_MIN
bool publish_insnavgeod
Whether or not to publish the INSNavGeodMsg message.
Rtk rtk
RTK corrections settings.
void handleTelegram(const std::shared_ptr< Telegram > &telegram)
Called every time a telegram is received.
std::string septentrio_receiver_type
Septentrio receiver type, either "gnss" or "ins".
std::unique_ptr< AsyncManagerBase > manager_
static const int8_t LEVER_ARM_MAX
TelegramHandler telegramHandler_
TelegramHandler.
bool read_from_pcap
Whether or not we are reading from a PCAP file.
bool publish_gpgsv
Whether or not to publish the GSV message.
uint32_t ip_server_port
VSM tcp port.
double ant_lever_y
INS antenna lever arm y-offset.
bool initializedIo_
Whether connecting was successful.