This class represents the ROsaic node, to be extended.. More...
#include <rosaic_node.hpp>
Public Member Functions | |
| void | configureRx () |
| Configures Rx: Which SBF/NMEA messages it should output and later correction settings. More... | |
| void | connect () |
| Calles the reconnect() method. More... | |
| void | defineMessages () |
| Defines which Rx messages to read and which ROS messages to publish. More... | |
| void | getROSParams () |
| Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file. 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... | |
| ROSaicNode () | |
Private Attributes | |
| std::string | ant_serial_nr_ |
| Serial number of your particular antenna. More... | |
| std::string | ant_type_ |
| Antenna type, from the list returned by the command "lstAntennaInfo, Overview". More... | |
| uint32_t | baudrate_ |
| Baudrate. 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... | |
| bool | connected_ |
| Whether connecting to Rx was successful. More... | |
| boost::condition_variable | connection_condition_ |
| boost::mutex | connection_mutex_ |
| std::string | datum_ |
| Datum to be used. 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 | device_ |
| Device port. More... | |
| std::string | hw_flow_control_ |
| HW flow control. More... | |
| std::string | mode_ |
| Type of NTRIP connection. More... | |
| std::string | mountpoint_ |
| Mountpoint for NTRIP service. More... | |
| std::string | ntrip_version_ |
| NTRIP version for NTRIP service. More... | |
| std::string | password_ |
| Password for NTRIP service. 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... | |
| bool | publish_attcoveuler_ |
| Whether or not to publish the rosaic::AttCovEuler message. More... | |
| bool | publish_atteuler_ |
| Whether or not to publish the rosaic::AttEuler message. More... | |
| bool | publish_gpgga_ |
| Whether or not to publish the GGA 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_gprmc_ |
| Whether or not to publish the RMC 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_pvtcartesian_ |
| Whether or not to publish the rosaic::PVTCartesian message. More... | |
| bool | publish_pvtgeodetic_ |
| Whether or not to publish the rosaic::PVTGeodetic message. More... | |
| float | reconnect_delay_s_ |
| Delay in seconds between reconnection attempts to the connection type specified in the parameter connection_type. More... | |
| ros::Timer | reconnect_timer_ |
| Our ROS timer governing the reconnection. More... | |
| std::string | rtcm_version_ |
| RTCM version for NTRIP service (if Rx does not have internet) More... | |
| bool | rx_has_internet_ |
| Whether Rx has internet or not. 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... | |
| 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_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... | |
| std::string | send_gga_ |
| Whether (and at which rate) or not to send GGA to the NTRIP caster. More... | |
| bool | serial_ |
| Whether yet-to-be-established connection to Rx will be serial or TCP. More... | |
| std::string | tcp_host_ |
| Host name of TCP server. More... | |
| std::string | tcp_port_ |
| TCP port number. More... | |
| std::string | username_ |
| Username for NTRIP service. More... | |
This class represents the ROsaic node, to be extended..
Definition at line 200 of file rosaic_node.hpp.
| 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.
| 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.
| void rosaic_node::ROSaicNode::connect | ( | ) |
Calles the reconnect() method.
Definition at line 488 of file rosaic_node.cpp.
| 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.
| 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.
| void rosaic_node::ROSaicNode::initializeIO | ( | ) |
Initializes the I/O handling.
Definition at line 445 of file rosaic_node.cpp.
| 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.
|
private |
Serial number of your particular antenna.
Definition at line 270 of file rosaic_node.hpp.
|
private |
Antenna type, from the list returned by the command "lstAntennaInfo, Overview".
Definition at line 268 of file rosaic_node.hpp.
|
private |
Baudrate.
Definition at line 246 of file rosaic_node.hpp.
|
private |
Hostname or IP address of the NTRIP caster to connect to.
Definition at line 274 of file rosaic_node.hpp.
|
private |
IP port number of NTRIP caster to connect to.
Definition at line 276 of file rosaic_node.hpp.
|
private |
Whether connecting to Rx was successful.
Definition at line 252 of file rosaic_node.hpp.
|
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.
|
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.
|
private |
Datum to be used.
Definition at line 254 of file rosaic_node.hpp.
|
private |
Marker-to-ARP offset in the eastward direction.
Definition at line 262 of file rosaic_node.hpp.
|
private |
Marker-to-ARP offset in the northward direction.
Definition at line 264 of file rosaic_node.hpp.
|
private |
Marker-to-ARP offset in the upward direction.
Definition at line 266 of file rosaic_node.hpp.
|
private |
Device port.
Definition at line 244 of file rosaic_node.hpp.
|
private |
HW flow control.
Definition at line 248 of file rosaic_node.hpp.
|
private |
Type of NTRIP connection.
Definition at line 272 of file rosaic_node.hpp.
|
private |
Mountpoint for NTRIP service.
Definition at line 282 of file rosaic_node.hpp.
|
private |
NTRIP version for NTRIP service.
Definition at line 284 of file rosaic_node.hpp.
|
private |
Password for NTRIP service.
Definition at line 280 of file rosaic_node.hpp.
|
private |
Polling period for PVT-related SBF blocks.
Definition at line 256 of file rosaic_node.hpp.
|
private |
Polling period for all other SBF blocks and NMEA messages.
Definition at line 258 of file rosaic_node.hpp.
|
private |
Whether or not to publish the rosaic::AttCovEuler message.
Definition at line 316 of file rosaic_node.hpp.
|
private |
Whether or not to publish the rosaic::AttEuler message.
Definition at line 314 of file rosaic_node.hpp.
|
private |
Whether or not to publish the GGA message.
Definition at line 298 of file rosaic_node.hpp.
|
private |
Whether or not to publish the GSA message.
Definition at line 302 of file rosaic_node.hpp.
|
private |
Whether or not to publish the GSV message.
Definition at line 304 of file rosaic_node.hpp.
|
private |
Whether or not to publish the RMC message.
Definition at line 300 of file rosaic_node.hpp.
|
private |
Whether or not to publish the rosaic::PosCovCartesian message.
Definition at line 310 of file rosaic_node.hpp.
|
private |
Whether or not to publish the rosaic::PosCovGeodetic message.
Definition at line 312 of file rosaic_node.hpp.
|
private |
Whether or not to publish the rosaic::PVTCartesian message.
Definition at line 306 of file rosaic_node.hpp.
|
private |
Whether or not to publish the rosaic::PVTGeodetic message.
Definition at line 308 of file rosaic_node.hpp.
|
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.
|
private |
Our ROS timer governing the reconnection.
Definition at line 294 of file rosaic_node.hpp.
|
private |
RTCM version for NTRIP service (if Rx does not have internet)
Definition at line 288 of file rosaic_node.hpp.
|
private |
Whether Rx has internet or not.
Definition at line 286 of file rosaic_node.hpp.
|
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.
|
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.
|
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.
|
private |
Whether (and at which rate) or not to send GGA to the NTRIP caster.
Definition at line 296 of file rosaic_node.hpp.
|
private |
Whether yet-to-be-established connection to Rx will be serial or TCP.
Definition at line 328 of file rosaic_node.hpp.
|
private |
Host name of TCP server.
Definition at line 324 of file rosaic_node.hpp.
|
private |
TCP port number.
Definition at line 326 of file rosaic_node.hpp.
|
private |
Username for NTRIP service.
Definition at line 278 of file rosaic_node.hpp.