ROSaic
Public Member Functions | Private Attributes
rosaic_node::ROSaicNode Class Reference

This class represents the ROsaic node, to be extended.. More...

#include <rosaic_node.hpp>

Collaboration diagram for rosaic_node::ROSaicNode:
Collaboration graph
[legend]

Public Member Functions

 ROSaicNode ()
 
void getROSParams ()
 Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file. More...
 
void defineMessages ()
 Defines which Rx messages to read and which ROS messages to publish. More...
 
void configureRx ()
 Configures Rx: Which SBF/NMEA messages it should output and later correction settings. More...
 
void initializeIO ()
 Initializes the I/O handling. More...
 
void reconnect (const ros::TimerEvent &event)
 Attempts to (re)connect every reconnect_delay_s_ seconds. More...
 
void connect ()
 Calles the reconnect() method. More...
 

Private Attributes

std::string device_
 Device port. More...
 
uint32_t baudrate_
 Baudrate. More...
 
std::string hw_flow_control_
 HW flow control. More...
 
std::string rx_serial_port_
 In case of serial communication to Rx, rx_serial_port_ specifies Rx's serial port connected to, e.g. USB1 or COM1. More...
 
bool connected_
 Whether connecting to Rx was successful. More...
 
std::string datum_
 Datum to be used. More...
 
uint32_t polling_period_pvt_
 Polling period for PVT-related SBF blocks. More...
 
uint32_t polling_period_rest_
 Polling period for all other SBF blocks and NMEA messages. More...
 
float reconnect_delay_s_
 Delay in seconds between reconnection attempts to the connection type specified in the parameter connection_type. More...
 
float delta_e_
 Marker-to-ARP offset in the eastward direction. More...
 
float delta_n_
 Marker-to-ARP offset in the northward direction. More...
 
float delta_u_
 Marker-to-ARP offset in the upward direction. More...
 
std::string ant_type_
 Antenna type, from the list returned by the command "lstAntennaInfo, Overview". More...
 
std::string ant_serial_nr_
 Serial number of your particular antenna. More...
 
std::string mode_
 Type of NTRIP connection. More...
 
std::string caster_
 Hostname or IP address of the NTRIP caster to connect to. More...
 
uint32_t caster_port_
 IP port number of NTRIP caster to connect to. More...
 
std::string username_
 Username for NTRIP service. More...
 
std::string password_
 Password for NTRIP service. More...
 
std::string mountpoint_
 Mountpoint for NTRIP service. More...
 
std::string ntrip_version_
 NTRIP version for NTRIP service. More...
 
bool rx_has_internet_
 Whether Rx has internet or not. More...
 
std::string rtcm_version_
 RTCM version for NTRIP service (if Rx does not have internet) More...
 
uint32_t rx_input_corrections_tcp_
 Rx TCP port number, e.g. 28785, on which Rx receives the corrections (can't be the same as main connection unless localhost concept is used) More...
 
std::string rx_input_corrections_serial_
 Rx serial port, e.g. USB2, on which Rx receives the corrections (can't be the same as main connection unless localhost concept is used) More...
 
ros::Timer reconnect_timer_
 Our ROS timer governing the reconnection. More...
 
std::string send_gga_
 Whether (and at which rate) or not to send GGA to the NTRIP caster. More...
 
bool publish_gpgga_
 Whether or not to publish the GGA message. More...
 
bool publish_gprmc_
 Whether or not to publish the RMC message. More...
 
bool publish_gpgsa_
 Whether or not to publish the GSA message. More...
 
bool publish_gpgsv_
 Whether or not to publish the GSV message. More...
 
bool publish_pvtcartesian_
 Whether or not to publish the rosaic::PVTCartesian message. More...
 
bool publish_pvtgeodetic_
 Whether or not to publish the rosaic::PVTGeodetic message. More...
 
bool publish_poscovcartesian_
 Whether or not to publish the rosaic::PosCovCartesian message. More...
 
bool publish_poscovgeodetic_
 Whether or not to publish the rosaic::PosCovGeodetic message. More...
 
bool publish_atteuler_
 Whether or not to publish the rosaic::AttEuler message. More...
 
bool publish_attcoveuler_
 Whether or not to publish the rosaic::AttCovEuler message. More...
 
boost::mutex connection_mutex_
 
boost::condition_variable connection_condition_
 
std::string tcp_host_
 Host name of TCP server. More...
 
std::string tcp_port_
 TCP port number. More...
 
bool serial_
 Whether yet-to-be-established connection to Rx will be serial or TCP. More...
 

Detailed Description

This class represents the ROsaic node, to be extended..

Definition at line 200 of file rosaic_node.hpp.

Constructor & Destructor Documentation

◆ ROSaicNode()

rosaic_node::ROSaicNode::ROSaicNode ( )

The constructor initializes and runs the Rosaic node, if all works out fine. It loads the user-defined ROS parameters, subscribes to Rx messages, and publishes requested ROS messages...

Definition at line 39 of file rosaic_node.cpp.

References configureRx(), connected_, connection_condition_, connection_mutex_, defineMessages(), getROSParams(), and initializeIO().

40 {
41  ROS_DEBUG("Called ROSaicNode() constructor..");
42 
43  // Parameters must be set before initializing IO
44  connected_ = false;
45  getROSParams();
46 
47  // Initializes Connection
48  initializeIO();
49 
50  // Subscribes to all requested Rx messages by adding entries to the C++ multimap
51  // storing the callback handlers and publishes ROS messages
53 
54  // Sends commands to the Rx regarding which SBF/NMEA messages it should output and sets all
55  // its necessary corrections-related parameters
56  boost::mutex::scoped_lock lock(connection_mutex_);
57  connection_condition_.wait(lock, [this](){return connected_;});
58  configureRx();
59 
60  // Since we already have a ros::Spin() elsewhere, we use waitForShutdown() here
61  ros::waitForShutdown();
62  ROS_DEBUG("Leaving ROSaicNode() constructor..");
63 }
boost::mutex connection_mutex_
void getROSParams()
Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file...
void defineMessages()
Defines which Rx messages to read and which ROS messages to publish.
void initializeIO()
Initializes the I/O handling.
boost::condition_variable connection_condition_
bool connected_
Whether connecting to Rx was successful.
void configureRx()
Configures Rx: Which SBF/NMEA messages it should output and later correction settings.
Definition: rosaic_node.cpp:70
Here is the call graph for this function:

Member Function Documentation

◆ configureRx()

void rosaic_node::ROSaicNode::configureRx ( )

Configures Rx: Which SBF/NMEA messages it should output and later correction settings.

The send() method of AsyncManager class is paramount for this purpose. Note that std::to_string() is from C++11 onwards only. Since ROSaic can be launched before booting the Rx, we have to watch out for escape characters that are sent by the Rx to indicate that it is in upgrade mode. Those characters would then be mingled with the first command we send to it in this method and could result in an invalid command. Hence we first enter command mode via "SSSSSSSSSS".

Definition at line 70 of file rosaic_node.cpp.

References ant_serial_nr_, ant_type_, caster_, caster_port_, parsing_utilities::convertUserPeriodToRxCommand(), datum_, delta_e_, delta_n_, delta_u_, device_, g_cd_condition, g_cd_mutex, g_cd_received, g_publish_diagnostics, g_publish_gpsfix, g_response_condition, g_response_mutex, g_response_received, g_rx_tcp_port, rosaic_node::IO, mode_, mountpoint_, ntrip_version_, password_, polling_period_pvt_, polling_period_rest_, publish_attcoveuler_, publish_atteuler_, publish_gpgga_, publish_gpgsa_, publish_gpgsv_, publish_gprmc_, publish_poscovcartesian_, publish_poscovgeodetic_, publish_pvtcartesian_, publish_pvtgeodetic_, rtcm_version_, rx_has_internet_, rx_input_corrections_serial_, rx_input_corrections_tcp_, rx_serial_port_, io_comm_rx::Comm_IO::send(), send_gga_, string_utilities::trimString(), and username_.

Referenced by ROSaicNode().

71 {
72  ROS_DEBUG("Called configureRx() method");
73 
74  // It is imperative to hold a lock on the mutex "g_response_mutex" while modifying the variable
75  // "g_response_received". Same for "g_cd_mutex" and "g_cd_received".
76  boost::mutex::scoped_lock lock(g_response_mutex);
77  boost::mutex::scoped_lock lock_cd(g_cd_mutex);
78 
79  // Escape sequence (escape from correction mode), ensuring that we can send our real commands afterwards...
80  IO.send("\x0DSSSSSSSSSSSSSSSSSSS\x0D\x0D");
81  // We wait for the connection descriptor before we send another command, otherwise the latter would not be processed.
82  g_cd_condition.wait(lock_cd, [](){return g_cd_received;});
83  g_cd_received = false;
84 
85  // Turning off all current SBF/NMEA output
86  IO.send("sso, all, none, none, off \x0D");
87  g_response_condition.wait(lock, [](){return g_response_received;});
88  g_response_received = false;
89  IO.send("sno, all, none, none, off \x0D");
90  g_response_condition.wait(lock, [](){return g_response_received;});
91  g_response_received = false;
92 
93  // Setting the datum to be used by the Rx (not the NMEA output though, which only provides MSL and undulation
94  // (by default with respect to WGS84), but not ellipsoidal height)
95  {
96  std::stringstream ss;
97  ss << "sgd, " << datum_ << "\x0D";
98  IO.send(ss.str());
99  }
100  g_response_condition.wait(lock, [](){return g_response_received;});
101  g_response_received = false;
102 
103  // Setting SBF/NMEA output of Rx
104  unsigned stream = 1;
105  boost::smatch match;
106  boost::regex_match(device_, match, boost::regex("(tcp|udp)://(.+):(\\d+)"));
107  std::string proto(match[1]);
108  std::string rx_port;
109  if (proto == "tcp")
110  {
111  rx_port = g_rx_tcp_port;
112  }
113  else
114  {
115  rx_port = rx_serial_port_;
116  }
119  std::string pvt_sec_or_msec;
120  std::string rest_sec_or_msec;
121  if (polling_period_pvt_ == 1000 || polling_period_pvt_ == 2000 || polling_period_pvt_ == 5000 ||
122  polling_period_pvt_ == 10000) pvt_sec_or_msec = "sec";
123  else pvt_sec_or_msec = "msec";
124  if (polling_period_rest_ == 1000 || polling_period_rest_ == 2000 || polling_period_rest_ == 5000 ||
125  polling_period_rest_ == 10000) rest_sec_or_msec = "sec";
126  else rest_sec_or_msec = "msec";
127 
128 
129  if (publish_gpgga_ == true)
130  {
131  std::stringstream ss;
132 
133  ss << "sno, Stream" << std::to_string(stream) << ", " << rx_port << ", GGA, " << pvt_sec_or_msec <<
134  std::to_string(rx_period_pvt) << "\x0D";
135  IO.send(ss.str());
136  ++stream;
137  g_response_condition.wait(lock, [](){return g_response_received;});
138  g_response_received = false;
139  }
140  if (publish_gprmc_ == true)
141  {
142  std::stringstream ss;
143 
144  ss << "sno, Stream" << std::to_string(stream) << ", " << rx_port << ", RMC, " << pvt_sec_or_msec <<
145  std::to_string(rx_period_pvt) << "\x0D";
146  IO.send(ss.str());
147  ++stream;
148  g_response_condition.wait(lock, [](){return g_response_received;});
149  g_response_received = false;
150  }
151  if (publish_gpgsa_ == true)
152  {
153  std::stringstream ss;
154 
155  ss << "sno, Stream" << std::to_string(stream) << ", " << rx_port << ", GSA, " << pvt_sec_or_msec <<
156  std::to_string(rx_period_pvt) << "\x0D";
157  IO.send(ss.str());
158  ++stream;
159  g_response_condition.wait(lock, [](){return g_response_received;});
160  g_response_received = false;
161  }
162  if (publish_gpgsv_ == true)
163  {
164  std::stringstream ss;
165 
166  ss << "sno, Stream" << std::to_string(stream) << ", " << rx_port << ", GSV, " << rest_sec_or_msec <<
167  std::to_string(rx_period_rest) << "\x0D";
168  IO.send(ss.str());
169  ++stream;
170  g_response_condition.wait(lock, [](){return g_response_received;});
171  g_response_received = false;
172  }
173  if (publish_pvtcartesian_ == true)
174  {
175  std::stringstream ss;
176  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", PVTCartesian, " << pvt_sec_or_msec <<
177  std::to_string(rx_period_pvt) << "\x0D";
178  IO.send(ss.str());
179  ++stream;
180  g_response_condition.wait(lock, [](){return g_response_received;});
181  g_response_received = false;
182  }
183  if (publish_pvtgeodetic_ == true)
184  {
185  std::stringstream ss;
186  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", PVTGeodetic, " << pvt_sec_or_msec <<
187  std::to_string(rx_period_pvt) << "\x0D";
188  IO.send(ss.str());
189  ++stream;
190  g_response_condition.wait(lock, [](){return g_response_received;});
191  g_response_received = false;
192  }
193  if (publish_poscovcartesian_ == true)
194  {
195  std::stringstream ss;
196  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", PosCovCartesian, " << pvt_sec_or_msec <<
197  std::to_string(rx_period_pvt) << "\x0D";
198  IO.send(ss.str());
199  ++stream;
200  g_response_condition.wait(lock, [](){return g_response_received;});
201  g_response_received = false;
202  }
203  if (publish_poscovgeodetic_ == true)
204  {
205  std::stringstream ss;
206  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", PosCovGeodetic, " << pvt_sec_or_msec <<
207  std::to_string(rx_period_pvt) << "\x0D";
208  IO.send(ss.str());
209  ++stream;
210  g_response_condition.wait(lock, [](){return g_response_received;});
211  g_response_received = false;
212  }
213  if (publish_atteuler_ == true)
214  {
215  std::stringstream ss;
216  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", AttEuler, " << rest_sec_or_msec <<
217  std::to_string(rx_period_rest) << "\x0D";
218  IO.send(ss.str());
219  ++stream;
220  g_response_condition.wait(lock, [](){return g_response_received;});
221  g_response_received = false;
222  }
223  if (publish_attcoveuler_ == true)
224  {
225  std::stringstream ss;
226  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", AttCovEuler, " << rest_sec_or_msec <<
227  std::to_string(rx_period_rest) << "\x0D";
228  IO.send(ss.str());
229  ++stream;
230  g_response_condition.wait(lock, [](){return g_response_received;});
231  g_response_received = false;
232  }
233  if (g_publish_gpsfix == true)
234  {
235  std::stringstream ss;
236  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", ChannelStatus, " << pvt_sec_or_msec <<
237  std::to_string(rx_period_pvt) << "\x0D";
238  IO.send(ss.str());
239  ++stream;
240  g_response_condition.wait(lock, [](){return g_response_received;});
241  g_response_received = false;
242  ss.str(std::string()); // avoids invoking the std::string constructor
243  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", MeasEpoch, " << pvt_sec_or_msec <<
244  std::to_string(rx_period_pvt) << "\x0D";
245  IO.send(ss.str());
246  ++stream;
247  g_response_condition.wait(lock, [](){return g_response_received;});
248  g_response_received = false;
249  ss.str(std::string());
250  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", DOP, " << pvt_sec_or_msec <<
251  std::to_string(rx_period_pvt) << "\x0D";
252  IO.send(ss.str());
253  ++stream;
254  g_response_condition.wait(lock, [](){return g_response_received;});
255  g_response_received = false;
256  ss.str(std::string());
257  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", VelCovGeodetic, " << pvt_sec_or_msec <<
258  std::to_string(rx_period_pvt) << "\x0D";
259  IO.send(ss.str());
260  ++stream;
261  g_response_condition.wait(lock, [](){return g_response_received;});
262  g_response_received = false;
263  }
264  if (g_publish_diagnostics == true)
265  {
266  std::stringstream ss;
267  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", ReceiverStatus, " << rest_sec_or_msec <<
268  std::to_string(rx_period_rest) << "\x0D";
269  IO.send(ss.str());
270  ++stream;
271  g_response_condition.wait(lock, [](){return g_response_received;});
272  g_response_received = false;
273  ss.str(std::string());
274  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", QualityInd, " << rest_sec_or_msec <<
275  std::to_string(rx_period_rest) << "\x0D";
276  IO.send(ss.str());
277  ++stream;
278  g_response_condition.wait(lock, [](){return g_response_received;});
279  g_response_received = false;
280  ss.str(std::string());
281  ss << "sso, Stream" << std::to_string(stream) << ", " << rx_port << ", ReceiverSetup, " << rest_sec_or_msec <<
282  std::to_string(rx_period_rest) << "\x0D";
283  IO.send(ss.str());
284  ++stream;
285  g_response_condition.wait(lock, [](){return g_response_received;});
286  g_response_received = false;
287  }
288 
289  // Setting the marker-to-ARP offsets. This comes after the "sso, ..., ReceiverSetup, ..." command,
290  // since the latter is only generated when a user-command is entered to change one or more values in the block.
291  {
292  std::stringstream ss;
293  ss << "sao, Main, " << string_utilities::trimString(std::to_string(delta_e_)) << ", " <<
294  string_utilities::trimString(std::to_string(delta_n_)) << ", " <<
295  string_utilities::trimString(std::to_string(delta_u_)) << ", \"" << ant_type_ << "\", \"" << ant_serial_nr_ <<
296  "\", 0 \x0D";
297  IO.send(ss.str());
298  }
299  g_response_condition.wait(lock, [](){return g_response_received;});
300  g_response_received = false;
301 
302  // Configuring the NTRIP connection
303  // First disable any existing NTRIP connection on NTR1
304  {
305  std::stringstream ss;
306  ss << "snts, NTR1, off \x0D";
307  IO.send(ss.str());
308  }
309  g_response_condition.wait(lock, [](){return g_response_received;});
310  g_response_received = false;
311  if (rx_has_internet_)
312  {
313  if (mode_ == "off")
314  {
315  }
316  else if (mode_ == "Client")
317  {
318  {
319  std::stringstream ss;
320  ss << "snts, NTR1, " << mode_ << ", " << caster_ << ", " << std::to_string(caster_port_) << ", " <<
321  username_ << ", " << password_ << ", " << mountpoint_ << ", " << ntrip_version_ << ", " << send_gga_ << " \x0D";
322  IO.send(ss.str());
323  }
324  g_response_condition.wait(lock, [](){return g_response_received;});
325  g_response_received = false;
326  }
327  else if (mode_ == "Client-Sapcorda")
328  {
329  {
330  std::stringstream ss;
331  ss << "snts, NTR1, Client-Sapcorda, , , , , , , , \x0D";
332  IO.send(ss.str());
333  }
334  g_response_condition.wait(lock, [](){return g_response_received;});
335  g_response_received = false;
336  }
337  else
338  {
339  ROS_ERROR("Invalid mode specified for NTRIP settings.");
340  }
341  }
342  else // Since the Rx does not have internet (and you will not be able to share it via USB),
343  //we need to forward the corrections ourselves, though not on the same port.
344  {
345  if (proto == "tcp")
346  {
347  {
348  std::stringstream ss;
349  // In case IPS1 was used before, old configuration is lost of course.
350  ss << "siss, IPS1, " << std::to_string(rx_input_corrections_tcp_) << ", TCP2Way \x0D";
351  IO.send(ss.str());
352  }
353  g_response_condition.wait(lock, [](){return g_response_received;});
354  g_response_received = false;
355  {
356  std::stringstream ss;
357  ss << "sno, Stream" << std::to_string(stream) << ", IPS1, GGA, " << pvt_sec_or_msec <<
358  std::to_string(rx_period_pvt) << " \x0D";
359  ++stream;
360  IO.send(ss.str());
361  }
362  g_response_condition.wait(lock, [](){return g_response_received;});
363  g_response_received = false;
364  }
365  {
366  std::stringstream ss;
367  if (proto == "tcp")
368  {
369  ss << "sdio, IPS1, " << rtcm_version_ << ", +SBF+NMEA \x0D";
370  }
371  else
372  {
373  ss << "sdio, " << rx_input_corrections_serial_ << ", " << rtcm_version_ << ", +SBF+NMEA \x0D";
374  }
375  IO.send(ss.str());
376  }
377  }
378  ROS_DEBUG("Leaving configureRx() method");
379 }
std::string rtcm_version_
RTCM version for NTRIP service (if Rx does not have internet)
uint32_t polling_period_pvt_
Polling period for PVT-related SBF blocks.
std::string password_
Password for NTRIP service.
bool publish_attcoveuler_
Whether or not to publish the rosaic::AttCovEuler message.
bool publish_gprmc_
Whether or not to publish the RMC message.
bool g_cd_received
Determines whether the connection descriptor was received from the Rx.
boost::mutex g_response_mutex
Mutex to control changes of global variable "g_response_received".
std::string g_rx_tcp_port
Rx TCP port, e.g. IP10 or IP11, to which ROSaic is connected to.
uint32_t polling_period_rest_
Polling period for all other SBF blocks and NMEA messages.
bool rx_has_internet_
Whether Rx has internet or not.
bool publish_pvtcartesian_
Whether or not to publish the rosaic::PVTCartesian message.
bool publish_poscovcartesian_
Whether or not to publish the rosaic::PosCovCartesian message.
std::string ant_type_
Antenna type, from the list returned by the command "lstAntennaInfo, Overview".
std::string rx_serial_port_
In case of serial communication to Rx, rx_serial_port_ specifies Rx&#39;s serial port connected to...
uint32_t rx_input_corrections_tcp_
Rx TCP port number, e.g. 28785, on which Rx receives the corrections (can&#39;t be the same as main conne...
bool publish_poscovgeodetic_
Whether or not to publish the rosaic::PosCovGeodetic message.
bool publish_atteuler_
Whether or not to publish the rosaic::AttEuler message.
float delta_n_
Marker-to-ARP offset in the northward direction.
bool g_publish_diagnostics
Whether or not to publish the diagnostic_msgs::DiagnosticArray message.
bool publish_pvtgeodetic_
Whether or not to publish the rosaic::PVTGeodetic message.
void send(std::string cmd)
bool publish_gpgsv_
Whether or not to publish the GSV message.
uint32_t caster_port_
IP port number of NTRIP caster to connect to.
boost::mutex g_cd_mutex
Mutex to control changes of global variable "g_cd_received".
std::string ant_serial_nr_
Serial number of your particular antenna.
std::string username_
Username for NTRIP service.
std::string mountpoint_
Mountpoint for NTRIP service.
bool publish_gpgga_
Whether or not to publish the GGA message.
boost::condition_variable g_cd_condition
Condition variable complementing "g_cd_mutex".
std::string mode_
Type of NTRIP connection.
std::string send_gga_
Whether (and at which rate) or not to send GGA to the NTRIP caster.
uint32_t convertUserPeriodToRxCommand(uint32_t period_user)
Transforms the input polling period [milliseconds] into a uint32_t number that can be appended to eit...
float delta_e_
Marker-to-ARP offset in the eastward direction.
std::string device_
Device port.
std::string rx_input_corrections_serial_
Rx serial port, e.g. USB2, on which Rx receives the corrections (can&#39;t be the same as main connection...
bool g_publish_gpsfix
Whether or not to publish the gps_common::GPSFix message.
std::string trimString(std::string str)
Removes trailing zeros from a string representing a float or double except for the first zero after t...
bool publish_gpgsa_
Whether or not to publish the GSA message.
std::string datum_
Datum to be used.
std::string caster_
Hostname or IP address of the NTRIP caster to connect to.
std::string ntrip_version_
NTRIP version for NTRIP service.
bool g_response_received
Determines whether a command reply was received from the Rx.
boost::condition_variable g_response_condition
Condition variable complementing "g_response_mutex".
io_comm_rx::Comm_IO IO
Handles communication with the Rx.
Definition: rosaic_node.hpp:96
float delta_u_
Marker-to-ARP offset in the upward direction.
Here is the call graph for this function:
Here is the caller graph for this function:

◆ connect()

void rosaic_node::ROSaicNode::connect ( )

Calles the reconnect() method.

Definition at line 488 of file rosaic_node.cpp.

References g_nh, reconnect(), reconnect_delay_s_, and reconnect_timer_.

Referenced by initializeIO().

489 {
490  ROS_DEBUG("Called connect() method");
491  ROS_DEBUG("Setting ROS timer for calling reconnect() method until connection succeds");
492  reconnect_timer_ = g_nh->createTimer(ros::Duration(reconnect_delay_s_), &ROSaicNode::reconnect, this);
493  reconnect_timer_.start();
494  ROS_DEBUG("Started ROS timer for calling reconnect() method until connection succeds");
495  ros::spin();
496  ROS_DEBUG("Leaving connect() method"); // This will never be output since ros::spin() is on the line above.
497 }
boost::shared_ptr< ros::NodeHandle > g_nh
void reconnect(const ros::TimerEvent &event)
Attempts to (re)connect every reconnect_delay_s_ seconds.
float reconnect_delay_s_
Delay in seconds between reconnection attempts to the connection type specified in the parameter conn...
ros::Timer reconnect_timer_
Our ROS timer governing the reconnection.
Here is the call graph for this function:
Here is the caller graph for this function:

◆ defineMessages()

void rosaic_node::ROSaicNode::defineMessages ( )

Defines which Rx messages to read and which ROS messages to publish.

initializeSerial is not self-contained: The for loop in Callbackhandlers' handle method would never open a specific handler unless the handler is added (=inserted) to the C++ map via this function. This way, the specific handler can be called, in which in turn RxMessage's read() method is called, thereby "message" occupied, and func_ (the handler we insert in this function) called with this "message".

Definition at line 569 of file rosaic_node.cpp.

References io_comm_rx::CallbackHandlers::callbackmap_, g_publish_diagnostics, g_publish_gpsfix, g_publish_gpst, g_publish_navsatfix, g_publish_pose, io_comm_rx::Comm_IO::getHandlers(), io_comm_rx::Comm_IO::handlers_, io_comm_rx::CallbackHandlers::insert(), rosaic_node::IO, publish_attcoveuler_, publish_atteuler_, publish_gpgga_, publish_gpgsa_, publish_gpgsv_, publish_gprmc_, publish_poscovcartesian_, publish_poscovgeodetic_, publish_pvtcartesian_, and publish_pvtgeodetic_.

Referenced by ROSaicNode().

570 {
571  ROS_DEBUG("Called defineMessages() method");
572 
573  if (publish_gpgga_ == true)
574  {
575  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::Gpgga>("$GPGGA");
576  }
577  if (publish_gprmc_ == true)
578  {
579  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::Gprmc>("$GPRMC");
580  }
581  if (publish_gpgsa_ == true)
582  {
583  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::Gpgsa>("$GPGSA");
584  }
585  if (publish_gpgsv_ == true)
586  {
587  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::Gpgsv>("$GPGSV");
588  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::Gpgsv>("$GLGSV");
589  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::Gpgsv>("$GAGSV");
590  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::Gpgsv>("$GBGSV");
591  }
592  if (publish_pvtcartesian_ == true)
593  {
594  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::PVTCartesian>("4006");
595  }
596  if (publish_pvtgeodetic_ == true)
597  {
598  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::PVTGeodetic>("4007");
599  }
600  if (publish_poscovcartesian_ == true)
601  {
602  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::PosCovCartesian>("5905");
603  }
604  if (publish_poscovgeodetic_ == true)
605  {
606  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::PosCovGeodetic>("5906");
607  }
608  if (publish_atteuler_ == true)
609  {
610  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::AttEuler>("5938");
611  }
612  if (publish_attcoveuler_ == true)
613  {
614  IO.handlers_.callbackmap_ = IO.getHandlers().insert<rosaic::AttCovEuler>("5939");
615  }
616  if (g_publish_gpst == true)
617  {
618  IO.handlers_.callbackmap_ = IO.getHandlers().insert<int32_t>("GPST");
619  }
620  if (g_publish_navsatfix == true)
621  {
622  if (publish_pvtgeodetic_ == false || publish_poscovgeodetic_ == false)
623  {
624  ROS_ERROR("For a proper NavSatFix message, please set the publish/pvtgeodetic and the publish/poscovgeodetic ROSaic parameters both to true.");
625  }
626  IO.handlers_.callbackmap_ = IO.getHandlers().insert<sensor_msgs::NavSatFix>("NavSatFix");
627  }
628  if (g_publish_gpsfix == true)
629  {
630  if (publish_pvtgeodetic_ == false || publish_poscovgeodetic_ == false)
631  {
632  ROS_ERROR("For a proper GPSFix message, please set the publish/pvtgeodetic and the publish/poscovgeodetic ROSaic parameters both to true.");
633  }
634  IO.handlers_.callbackmap_ = IO.getHandlers().insert<gps_common::GPSFix>("GPSFix");
635  // The following blocks are never published, yet are needed for the construction of the GPSFix message, hence we have empty callbacks.
636  IO.handlers_.callbackmap_ = IO.getHandlers().insert<int32_t>("4013"); // ChannelStatus block
637  IO.handlers_.callbackmap_ = IO.getHandlers().insert<int32_t>("4027"); // MeasEpoch block
638  IO.handlers_.callbackmap_ = IO.getHandlers().insert<int32_t>("4001"); // DOP block
639  IO.handlers_.callbackmap_ = IO.getHandlers().insert<int32_t>("5908"); // VelCovGeodetic block
640  }
641  if (g_publish_pose == true)
642  {
643  if (publish_pvtgeodetic_ == false || publish_poscovgeodetic_ == false || publish_atteuler_ == false ||
644  publish_attcoveuler_ == false)
645  {
646  ROS_ERROR("For a proper PoseWithCovarianceStamped message, please set the publish/pvtgeodetic, publish/poscovgeodetic, publish_atteuler and publish_attcoveuler ROSaic parameters all to true.");
647  }
648  IO.handlers_.callbackmap_ = IO.getHandlers().insert<geometry_msgs::PoseWithCovarianceStamped>("PoseWithCovarianceStamped");
649  }
650  if (g_publish_diagnostics == true)
651  {
652  IO.handlers_.callbackmap_ = IO.getHandlers().insert<diagnostic_msgs::DiagnosticArray>("DiagnosticArray");
653  IO.handlers_.callbackmap_ = IO.getHandlers().insert<int32_t>("4014"); // ReceiverStatus block
654  IO.handlers_.callbackmap_ = IO.getHandlers().insert<int32_t>("4082"); // QualityInd block
655  IO.handlers_.callbackmap_ = IO.getHandlers().insert<int32_t>("5902"); // ReceiverSetup block
656  }
657  // so on and so forth...
658  ROS_DEBUG("Leaving defineMessages() method");
659 }
bool publish_attcoveuler_
Whether or not to publish the rosaic::AttCovEuler message.
bool publish_gprmc_
Whether or not to publish the RMC message.
bool publish_pvtcartesian_
Whether or not to publish the rosaic::PVTCartesian message.
bool publish_poscovcartesian_
Whether or not to publish the rosaic::PosCovCartesian message.
CallbackMap insert(std::string message_key)
Adds a pair to the multimap "callbackmap_", with the message_key being the key.
CallbackHandlers getHandlers() const
bool publish_poscovgeodetic_
Whether or not to publish the rosaic::PosCovGeodetic message.
bool publish_atteuler_
Whether or not to publish the rosaic::AttEuler message.
bool g_publish_diagnostics
Whether or not to publish the diagnostic_msgs::DiagnosticArray message.
bool publish_pvtgeodetic_
Whether or not to publish the rosaic::PVTGeodetic message.
bool publish_gpgsv_
Whether or not to publish the GSV message.
bool g_publish_pose
Whether or not to publish the geometry_msgs::PoseWithCovarianceStamped message.
bool publish_gpgga_
Whether or not to publish the GGA message.
bool g_publish_navsatfix
Whether or not to publish the sensor_msgs::NavSatFix message.
CallbackHandlers handlers_
Callback handlers for the inwards streaming messages.
bool g_publish_gpsfix
Whether or not to publish the gps_common::GPSFix message.
bool publish_gpgsa_
Whether or not to publish the GSA message.
bool g_publish_gpst
Whether or not to publish the sensor_msgs::TimeReference message with GPST.
io_comm_rx::Comm_IO IO
Handles communication with the Rx.
Definition: rosaic_node.hpp:96
Here is the call graph for this function:
Here is the caller graph for this function:

◆ getROSParams()

void rosaic_node::ROSaicNode::getROSParams ( )

Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file.

The other ROSaic parameters are specified via the command line.

Definition at line 380 of file rosaic_node.cpp.

References ant_serial_nr_, ant_type_, baudrate_, caster_, caster_port_, datum_, delta_e_, delta_n_, delta_u_, device_, g_nh, rosaic_node::getROSInt(), hw_flow_control_, mode_, mountpoint_, ntrip_version_, password_, polling_period_pvt_, polling_period_rest_, publish_attcoveuler_, publish_atteuler_, publish_gpgga_, publish_gpgsa_, publish_gpgsv_, publish_gprmc_, publish_poscovcartesian_, publish_poscovgeodetic_, publish_pvtcartesian_, publish_pvtgeodetic_, reconnect_delay_s_, rtcm_version_, rx_has_internet_, rx_input_corrections_serial_, rx_input_corrections_tcp_, rx_serial_port_, send_gga_, and username_.

Referenced by ROSaicNode().

381 {
382  // Communication parameters
383  g_nh->param("device", device_, std::string("/dev/ttyACM0"));
384  getROSInt("serial/baudrate", baudrate_, static_cast<uint32_t>(115200));
385  g_nh->param("serial/hw_flow_control", hw_flow_control_, std::string("off"));
386  g_nh->param("serial/rx_serial_port", rx_serial_port_, std::string("USB1"));
387 
388  g_nh->param("reconnect_delay_s", reconnect_delay_s_, 4.0f);
389 
390  // Polling period parameters
391  getROSInt("polling_period/pvt", polling_period_pvt_, static_cast<uint32_t>(1000));
393  && polling_period_pvt_ != 200 && polling_period_pvt_ != 250 && polling_period_pvt_ != 500 && polling_period_pvt_ != 1000
394  && polling_period_pvt_ != 2000 && polling_period_pvt_ != 5000 && polling_period_pvt_ != 10000)
395  {
396  ROS_ERROR("Please specify a valid polling period for PVT-related SBF blocks and NMEA messages.");
397  }
398  getROSInt("polling_period/rest", polling_period_rest_, static_cast<uint32_t>(1000));
401  && polling_period_rest_ != 2000 && polling_period_rest_ != 5000 && polling_period_rest_ != 10000)
402  {
403  ROS_ERROR("Please specify a valid polling period for PVT-unrelated SBF blocks and NMEA messages.");
404  }
405 
406  // Datum and marker-to-ARP offset
407  g_nh->param("datum", datum_, std::string("ETRS89"));
408  g_nh->param("ant_type", ant_type_, std::string("Unknown"));
409  g_nh->param("ant_serial_nr", ant_serial_nr_, std::string("Unknown"));
410  g_nh->param("marker_to_arp/delta_e", delta_e_, 0.0f);
411  g_nh->param("marker_to_arp/delta_n", delta_n_, 0.0f);
412  g_nh->param("marker_to_arp/delta_u", delta_u_, 0.0f);
413 
414  // Correction service parameters
415  g_nh->param("ntrip_settings/mode", mode_, std::string("off"));
416  g_nh->param("ntrip_settings/caster", caster_, std::string());
417  getROSInt("ntrip_settings/caster_port", caster_port_, static_cast<uint32_t>(0));
418  g_nh->param("ntrip_settings/username", username_, std::string());
419  g_nh->param("ntrip_settings/password", password_, std::string());
420  g_nh->param("ntrip_settings/mountpoint", mountpoint_, std::string());
421  g_nh->param("ntrip_settings/ntrip_version", ntrip_version_, std::string("v2"));
422  g_nh->param("ntrip_settings/send_gga", send_gga_, std::string("auto"));
423  g_nh->param("ntrip_settings/rx_has_internet", rx_has_internet_, false);
424  g_nh->param("ntrip_settings/rtcm_version", rtcm_version_, std::string("RTCMv3"));
425  getROSInt("ntrip_settings/rx_input_corrections_tcp", rx_input_corrections_tcp_, static_cast<uint32_t>(28785));
426  g_nh->param("ntrip_settings/rx_input_corrections_serial", rx_input_corrections_serial_, std::string("USB2"));
427 
428  // Publishing parameters, the others remained global since they need to be accessed in the callbackhandlers.hpp file
429  g_nh->param("publish/gpgga", publish_gpgga_, true);
430  g_nh->param("publish/gprmc", publish_gprmc_, true);
431  g_nh->param("publish/gpgsa", publish_gpgsa_, true);
432  g_nh->param("publish/gpgsv", publish_gpgsv_, true);
433  g_nh->param("publish/pvtcartesian", publish_pvtcartesian_, true);
434  g_nh->param("publish/pvtgeodetic", publish_pvtgeodetic_, true);
435  g_nh->param("publish/poscovcartesian", publish_poscovcartesian_, true);
436  g_nh->param("publish/poscovgeodetic", publish_poscovgeodetic_, true);
437  g_nh->param("publish/atteuler", publish_atteuler_, true);
438  g_nh->param("publish/attcoveuler", publish_attcoveuler_, true);
439 
440  // To be implemented: RTCM, setting datum, raw data settings, PPP, SBAS, fix mode...
441  ROS_DEBUG("Finished getROSParams() method");
442 
443 }
std::string rtcm_version_
RTCM version for NTRIP service (if Rx does not have internet)
uint32_t polling_period_pvt_
Polling period for PVT-related SBF blocks.
boost::shared_ptr< ros::NodeHandle > g_nh
std::string password_
Password for NTRIP service.
bool publish_attcoveuler_
Whether or not to publish the rosaic::AttCovEuler message.
bool publish_gprmc_
Whether or not to publish the RMC message.
uint32_t polling_period_rest_
Polling period for all other SBF blocks and NMEA messages.
bool rx_has_internet_
Whether Rx has internet or not.
bool publish_pvtcartesian_
Whether or not to publish the rosaic::PVTCartesian message.
bool publish_poscovcartesian_
Whether or not to publish the rosaic::PosCovCartesian message.
std::string ant_type_
Antenna type, from the list returned by the command "lstAntennaInfo, Overview".
std::string rx_serial_port_
In case of serial communication to Rx, rx_serial_port_ specifies Rx&#39;s serial port connected to...
uint32_t rx_input_corrections_tcp_
Rx TCP port number, e.g. 28785, on which Rx receives the corrections (can&#39;t be the same as main conne...
bool publish_poscovgeodetic_
Whether or not to publish the rosaic::PosCovGeodetic message.
bool publish_atteuler_
Whether or not to publish the rosaic::AttEuler message.
float delta_n_
Marker-to-ARP offset in the northward direction.
bool publish_pvtgeodetic_
Whether or not to publish the rosaic::PVTGeodetic message.
bool publish_gpgsv_
Whether or not to publish the GSV message.
uint32_t caster_port_
IP port number of NTRIP caster to connect to.
std::string ant_serial_nr_
Serial number of your particular antenna.
uint32_t baudrate_
Baudrate.
std::string username_
Username for NTRIP service.
std::string mountpoint_
Mountpoint for NTRIP service.
bool publish_gpgga_
Whether or not to publish the GGA message.
bool getROSInt(const std::string &key, U &u)
Gets an integer or unsigned integer value from the parameter server.
float reconnect_delay_s_
Delay in seconds between reconnection attempts to the connection type specified in the parameter conn...
std::string mode_
Type of NTRIP connection.
std::string send_gga_
Whether (and at which rate) or not to send GGA to the NTRIP caster.
float delta_e_
Marker-to-ARP offset in the eastward direction.
std::string device_
Device port.
std::string rx_input_corrections_serial_
Rx serial port, e.g. USB2, on which Rx receives the corrections (can&#39;t be the same as main connection...
bool publish_gpgsa_
Whether or not to publish the GSA message.
std::string datum_
Datum to be used.
std::string caster_
Hostname or IP address of the NTRIP caster to connect to.
std::string ntrip_version_
NTRIP version for NTRIP service.
float delta_u_
Marker-to-ARP offset in the upward direction.
std::string hw_flow_control_
HW flow control.
Here is the call graph for this function:
Here is the caller graph for this function:

◆ initializeIO()

void rosaic_node::ROSaicNode::initializeIO ( )

Initializes the I/O handling.

Definition at line 445 of file rosaic_node.cpp.

References connect(), device_, serial_, tcp_host_, and tcp_port_.

Referenced by ROSaicNode().

446 {
447  ROS_DEBUG("Called initializeIO() method");
448  boost::smatch match;
449  // In fact: smatch is a typedef of match_results<string::const_iterator>
450  if (boost::regex_match(device_, match, boost::regex("(tcp)://(.+):(\\d+)")))
451  // \d means decimal, however, in the regular expression, the \ is a special character, which needs
452  // to be escaped on its own as well..
453  // Note that regex_match can be used with a smatch object to store results, or without. In any case,
454  // true is returned if and only if it matches the !complete! string.
455  {
456  // The first sub_match (index 0) contained in a match_result always represents the full match
457  // within a target sequence made by a regex, and subsequent sub_matches represent sub-expression
458  // matches corresponding in sequence to the left parenthesis delimiting the sub-expression in the regex,
459  // i.e. $n Perl is equivalent to m[n] in boost regex.
460  std::string proto(match[1]);
461  if (proto == "tcp")
462  {
463  tcp_host_ = match[2];
464  tcp_port_ = match[3];
465 
466  serial_ = false;
467  boost::thread temporary_thread(boost::bind(&ROSaicNode::connect, this));
468  temporary_thread.detach();
469  }
470  else
471  {
472  {
473  std::stringstream ss;
474  ss << "Protocol '" << proto << "' is unsupported.";
475  ROS_ERROR("%s", ss.str().c_str());
476  }
477  }
478  }
479  else
480  {
481  serial_ = true;
482  boost::thread temporary_thread(boost::bind(&ROSaicNode::connect, this));
483  temporary_thread.detach();
484  }
485  ROS_DEBUG("Leaving initializeIO() method");
486 }
bool serial_
Whether yet-to-be-established connection to Rx will be serial or TCP.
void connect()
Calles the reconnect() method.
std::string tcp_port_
TCP port number.
std::string tcp_host_
Host name of TCP server.
std::string device_
Device port.
Here is the call graph for this function:
Here is the caller graph for this function:

◆ reconnect()

void rosaic_node::ROSaicNode::reconnect ( const ros::TimerEvent &  event)

Attempts to (re)connect every reconnect_delay_s_ seconds.

In serial mode (not USB, since the Rx port is then called USB1 or USB2), please ensure that you are connected to the Rx's COM1, COM2 or COM3 port, !if! you employ UART hardware flow control.

Definition at line 501 of file rosaic_node.cpp.

References baudrate_, connected_, connection_condition_, connection_mutex_, device_, hw_flow_control_, io_comm_rx::Comm_IO::initializeSerial(), io_comm_rx::Comm_IO::initializeTCP(), rosaic_node::IO, reconnect_timer_, serial_, tcp_host_, and tcp_port_.

Referenced by connect().

502 {
503  ROS_DEBUG("Called reconnect() method");
504  if (connected_ == true)
505  {
506  reconnect_timer_.stop();
507  ROS_DEBUG("Stopped ROS timer since successully connected.");
508  }
509  else
510  {
511  if (serial_)
512  {
513  bool initialize_serial_return = false;
514  try
515  {
516  ROS_INFO("Connecting serially to device %s, targeted baudrate: %u", device_.c_str(), baudrate_);
517  initialize_serial_return = IO.initializeSerial(device_, baudrate_, hw_flow_control_);
518  }
519  catch (std::runtime_error& e)
520  {
521  {
522  std::stringstream ss;
523  ss << "IO.initializeSerial() failed for device " << device_ << " due to: " << e.what();
524  ROS_ERROR("%s", ss.str().c_str());
525  }
526  }
527  if (initialize_serial_return)
528  {
529  boost::mutex::scoped_lock lock(connection_mutex_);
530  connected_ = true;
531  lock.unlock();
532  connection_condition_.notify_one();
533  }
534  }
535  else
536  {
537  bool initialize_tcp_return = false;
538  try
539  {
540  ROS_INFO("Connecting to tcp://%s:%s ...", tcp_host_.c_str(), tcp_port_.c_str());
541  initialize_tcp_return = IO.initializeTCP(tcp_host_, tcp_port_);
542  }
543  catch (std::runtime_error& e)
544  {
545  {
546  std::stringstream ss;
547  ss << "IO.initializeTCP() failed for host " << tcp_host_ << " on port " << tcp_port_ <<
548  " due to: " << e.what();
549  ROS_ERROR("%s", ss.str().c_str());
550  }
551  }
552  if (initialize_tcp_return)
553  {
554  boost::mutex::scoped_lock lock(connection_mutex_);
555  connected_ = true;
556  lock.unlock();
557  connection_condition_.notify_one();
558  }
559  }
560  }
561  ROS_DEBUG("Leaving reconnect() method");
562 }
boost::mutex connection_mutex_
bool serial_
Whether yet-to-be-established connection to Rx will be serial or TCP.
bool initializeTCP(std::string host, std::string port)
Initializes the TCP I/O.
bool initializeSerial(std::string port, uint32_t baudrate=115200, std::string flowcontrol="None")
Initializes the serial port.
std::string tcp_port_
TCP port number.
boost::condition_variable connection_condition_
uint32_t baudrate_
Baudrate.
std::string tcp_host_
Host name of TCP server.
bool connected_
Whether connecting to Rx was successful.
std::string device_
Device port.
ros::Timer reconnect_timer_
Our ROS timer governing the reconnection.
io_comm_rx::Comm_IO IO
Handles communication with the Rx.
Definition: rosaic_node.hpp:96
std::string hw_flow_control_
HW flow control.
Here is the call graph for this function:
Here is the caller graph for this function:

Field Documentation

◆ ant_serial_nr_

std::string rosaic_node::ROSaicNode::ant_serial_nr_
private

Serial number of your particular antenna.

Definition at line 270 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ ant_type_

std::string rosaic_node::ROSaicNode::ant_type_
private

Antenna type, from the list returned by the command "lstAntennaInfo, Overview".

Definition at line 268 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ baudrate_

uint32_t rosaic_node::ROSaicNode::baudrate_
private

Baudrate.

Definition at line 246 of file rosaic_node.hpp.

Referenced by getROSParams(), and reconnect().

◆ caster_

std::string rosaic_node::ROSaicNode::caster_
private

Hostname or IP address of the NTRIP caster to connect to.

Definition at line 274 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ caster_port_

uint32_t rosaic_node::ROSaicNode::caster_port_
private

IP port number of NTRIP caster to connect to.

Definition at line 276 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ connected_

bool rosaic_node::ROSaicNode::connected_
private

Whether connecting to Rx was successful.

Definition at line 252 of file rosaic_node.hpp.

Referenced by reconnect(), and ROSaicNode().

◆ connection_condition_

boost::condition_variable rosaic_node::ROSaicNode::connection_condition_
private

Since the configureRx() method should only be called once the connection was established, we need the threads to communicate this to each other. Associated condition variable..

Definition at line 322 of file rosaic_node.hpp.

Referenced by reconnect(), and ROSaicNode().

◆ connection_mutex_

boost::mutex rosaic_node::ROSaicNode::connection_mutex_
private

Since the configureRx() method should only be called once the connection was established, we need the threads to communicate this to each other. Associated mutex..

Definition at line 319 of file rosaic_node.hpp.

Referenced by reconnect(), and ROSaicNode().

◆ datum_

std::string rosaic_node::ROSaicNode::datum_
private

Datum to be used.

Definition at line 254 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ delta_e_

float rosaic_node::ROSaicNode::delta_e_
private

Marker-to-ARP offset in the eastward direction.

Definition at line 262 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ delta_n_

float rosaic_node::ROSaicNode::delta_n_
private

Marker-to-ARP offset in the northward direction.

Definition at line 264 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ delta_u_

float rosaic_node::ROSaicNode::delta_u_
private

Marker-to-ARP offset in the upward direction.

Definition at line 266 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ device_

std::string rosaic_node::ROSaicNode::device_
private

Device port.

Definition at line 244 of file rosaic_node.hpp.

Referenced by configureRx(), getROSParams(), initializeIO(), and reconnect().

◆ hw_flow_control_

std::string rosaic_node::ROSaicNode::hw_flow_control_
private

HW flow control.

Definition at line 248 of file rosaic_node.hpp.

Referenced by getROSParams(), and reconnect().

◆ mode_

std::string rosaic_node::ROSaicNode::mode_
private

Type of NTRIP connection.

Definition at line 272 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ mountpoint_

std::string rosaic_node::ROSaicNode::mountpoint_
private

Mountpoint for NTRIP service.

Definition at line 282 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ ntrip_version_

std::string rosaic_node::ROSaicNode::ntrip_version_
private

NTRIP version for NTRIP service.

Definition at line 284 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ password_

std::string rosaic_node::ROSaicNode::password_
private

Password for NTRIP service.

Definition at line 280 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ polling_period_pvt_

uint32_t rosaic_node::ROSaicNode::polling_period_pvt_
private

Polling period for PVT-related SBF blocks.

Definition at line 256 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ polling_period_rest_

uint32_t rosaic_node::ROSaicNode::polling_period_rest_
private

Polling period for all other SBF blocks and NMEA messages.

Definition at line 258 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ publish_attcoveuler_

bool rosaic_node::ROSaicNode::publish_attcoveuler_
private

Whether or not to publish the rosaic::AttCovEuler message.

Definition at line 316 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_atteuler_

bool rosaic_node::ROSaicNode::publish_atteuler_
private

Whether or not to publish the rosaic::AttEuler message.

Definition at line 314 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_gpgga_

bool rosaic_node::ROSaicNode::publish_gpgga_
private

Whether or not to publish the GGA message.

Definition at line 298 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_gpgsa_

bool rosaic_node::ROSaicNode::publish_gpgsa_
private

Whether or not to publish the GSA message.

Definition at line 302 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_gpgsv_

bool rosaic_node::ROSaicNode::publish_gpgsv_
private

Whether or not to publish the GSV message.

Definition at line 304 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_gprmc_

bool rosaic_node::ROSaicNode::publish_gprmc_
private

Whether or not to publish the RMC message.

Definition at line 300 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_poscovcartesian_

bool rosaic_node::ROSaicNode::publish_poscovcartesian_
private

Whether or not to publish the rosaic::PosCovCartesian message.

Definition at line 310 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_poscovgeodetic_

bool rosaic_node::ROSaicNode::publish_poscovgeodetic_
private

Whether or not to publish the rosaic::PosCovGeodetic message.

Definition at line 312 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_pvtcartesian_

bool rosaic_node::ROSaicNode::publish_pvtcartesian_
private

Whether or not to publish the rosaic::PVTCartesian message.

Definition at line 306 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ publish_pvtgeodetic_

bool rosaic_node::ROSaicNode::publish_pvtgeodetic_
private

Whether or not to publish the rosaic::PVTGeodetic message.

Definition at line 308 of file rosaic_node.hpp.

Referenced by configureRx(), defineMessages(), and getROSParams().

◆ reconnect_delay_s_

float rosaic_node::ROSaicNode::reconnect_delay_s_
private

Delay in seconds between reconnection attempts to the connection type specified in the parameter connection_type.

Definition at line 260 of file rosaic_node.hpp.

Referenced by connect(), and getROSParams().

◆ reconnect_timer_

ros::Timer rosaic_node::ROSaicNode::reconnect_timer_
private

Our ROS timer governing the reconnection.

Definition at line 294 of file rosaic_node.hpp.

Referenced by connect(), and reconnect().

◆ rtcm_version_

std::string rosaic_node::ROSaicNode::rtcm_version_
private

RTCM version for NTRIP service (if Rx does not have internet)

Definition at line 288 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ rx_has_internet_

bool rosaic_node::ROSaicNode::rx_has_internet_
private

Whether Rx has internet or not.

Definition at line 286 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ rx_input_corrections_serial_

std::string rosaic_node::ROSaicNode::rx_input_corrections_serial_
private

Rx serial port, e.g. USB2, on which Rx receives the corrections (can't be the same as main connection unless localhost concept is used)

Definition at line 292 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ rx_input_corrections_tcp_

uint32_t rosaic_node::ROSaicNode::rx_input_corrections_tcp_
private

Rx TCP port number, e.g. 28785, on which Rx receives the corrections (can't be the same as main connection unless localhost concept is used)

Definition at line 290 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ rx_serial_port_

std::string rosaic_node::ROSaicNode::rx_serial_port_
private

In case of serial communication to Rx, rx_serial_port_ specifies Rx's serial port connected to, e.g. USB1 or COM1.

Definition at line 250 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ send_gga_

std::string rosaic_node::ROSaicNode::send_gga_
private

Whether (and at which rate) or not to send GGA to the NTRIP caster.

Definition at line 296 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().

◆ serial_

bool rosaic_node::ROSaicNode::serial_
private

Whether yet-to-be-established connection to Rx will be serial or TCP.

Definition at line 328 of file rosaic_node.hpp.

Referenced by initializeIO(), and reconnect().

◆ tcp_host_

std::string rosaic_node::ROSaicNode::tcp_host_
private

Host name of TCP server.

Definition at line 324 of file rosaic_node.hpp.

Referenced by initializeIO(), and reconnect().

◆ tcp_port_

std::string rosaic_node::ROSaicNode::tcp_port_
private

TCP port number.

Definition at line 326 of file rosaic_node.hpp.

Referenced by initializeIO(), and reconnect().

◆ username_

std::string rosaic_node::ROSaicNode::username_
private

Username for NTRIP service.

Definition at line 278 of file rosaic_node.hpp.

Referenced by configureRx(), and getROSParams().


The documentation for this class was generated from the following files: