Handles callbacks when reading NMEA/SBF messages. More...
#include <boost/foreach.hpp>#include <boost/function.hpp>#include <boost/thread.hpp>#include <boost/thread/condition.hpp>#include <boost/tokenizer.hpp>#include <boost/algorithm/string/join.hpp>#include <boost/date_time/posix_time/posix_time.hpp>#include <boost/asio.hpp>#include <boost/bind.hpp>#include <boost/format.hpp>#include <boost/asio/serial_port.hpp>#include <boost/thread/mutex.hpp>#include <rosaic/communication/rx_message.hpp>#include <algorithm>

Go to the source code of this file.
Classes | |
| class | io_comm_rx::AbstractCallbackHandler |
| class | io_comm_rx::CallbackHandler< T > |
| Abstract class representing a generic callback handler, includes high-level functionality such as wait. More... | |
| class | io_comm_rx::CallbackHandlers |
| Represents ensemble of (to be constructed) ROS messages, to be handled at once by this class. More... | |
Namespaces | |
| io_comm_rx | |
Macros | |
| #define | MAX_NMEA_SIZE 89 |
| #define | MIN_NMEA_SIZE 9 |
Variables | |
| bool | g_attcoveuler_has_arrived_gpsfix |
| For GPSFix: Whether the AttCovEuler block of the current epoch has arrived or not. More... | |
| bool | g_attcoveuler_has_arrived_pose |
| For PoseWithCovarianceStamped: Whether the AttCovEuler block of the current epoch has arrived or not. More... | |
| bool | g_atteuler_has_arrived_gpsfix |
| For GPSFix: Whether the AttEuler block of the current epoch has arrived or not. More... | |
| bool | g_atteuler_has_arrived_pose |
| For PoseWithCovarianceStamped: Whether the AttEuler block of the current epoch has arrived or not. More... | |
| boost::condition_variable | g_cd_condition |
| Condition variable complementing "g_cd_mutex". More... | |
| uint32_t | g_cd_count |
| Since after SSSSSSSSSSS we need to wait for second connection descriptor, we have to count the connection descriptors. More... | |
| boost::mutex | g_cd_mutex |
| Mutex to control changes of global variable "g_cd_received". More... | |
| bool | g_cd_received |
| Determines whether the connection descriptor was received from the Rx. More... | |
| bool | g_channelstatus_has_arrived_gpsfix |
| For GPSFix: Whether the ChannelStatus block of the current epoch has arrived or not. More... | |
| bool | g_dop_has_arrived_gpsfix |
| For GPSFix: Whether the DOP block of the current epoch has arrived or not. More... | |
| bool | g_measepoch_has_arrived_gpsfix |
| For GPSFix: Whether the MeasEpoch block of the current epoch has arrived or not. More... | |
| bool | g_poscovgeodetic_has_arrived_gpsfix |
| For GPSFix: Whether the PosCovGeodetic block of the current epoch has arrived or not. More... | |
| bool | g_poscovgeodetic_has_arrived_navsatfix |
| For NavSatFix: Whether the PosCovGeodetic block of the current epoch has arrived or not. More... | |
| bool | g_poscovgeodetic_has_arrived_pose |
| For PoseWithCovarianceStamped: Whether the PosCovGeodetic block of the current epoch has arrived or not. More... | |
| bool | g_publish_diagnostics |
| Whether or not to publish the diagnostic_msgs::DiagnosticArray message. More... | |
| bool | g_publish_gpsfix |
| Whether or not to publish the gps_common::GPSFix message. More... | |
| bool | g_publish_gpst |
| Whether or not to publish the sensor_msgs::TimeReference message with GPST. More... | |
| bool | g_publish_navsatfix |
| Whether or not to publish the sensor_msgs::NavSatFix message. More... | |
| bool | g_publish_pose |
| Whether or not to publish the geometry_msgs::PoseWithCovarianceStamped message. More... | |
| bool | g_pvtgeodetic_has_arrived_gpsfix |
| For GPSFix: Whether the PVTGeodetic block of the current epoch has arrived or not. More... | |
| bool | g_pvtgeodetic_has_arrived_navsatfix |
| For NavSatFix: Whether the PVTGeodetic block of the current epoch has arrived or not. More... | |
| bool | g_pvtgeodetic_has_arrived_pose |
| For PoseWithCovarianceStamped: Whether the PVTGeodetic block of the current epoch has arrived or not. More... | |
| bool | g_qualityind_has_arrived_diagnostics |
| For DiagnosticArray: Whether the QualityInd block of the current epoch has arrived or not. More... | |
| bool | g_receiverstatus_has_arrived_diagnostics |
| For DiagnosticArray: Whether the ReceiverStatus block of the current epoch has arrived or not. More... | |
| boost::condition_variable | g_response_condition |
| Condition variable complementing "g_response_mutex". More... | |
| boost::mutex | g_response_mutex |
| Mutex to control changes of global variable "g_response_received". More... | |
| bool | g_response_received |
| Determines whether a command reply was received from the Rx. More... | |
| std::string | g_rx_tcp_port |
| Rx TCP port, e.g. IP10 or IP11, to which ROSaic is connected to. More... | |
| bool | g_velcovgeodetic_has_arrived_gpsfix |
| For GPSFix: Whether the VelCovGeodetic block of the current epoch has arrived or not. More... | |
Handles callbacks when reading NMEA/SBF messages.
Definition in file callback_handlers.hpp.
| #define MAX_NMEA_SIZE 89 |
Definition at line 67 of file callback_handlers.hpp.
| #define MIN_NMEA_SIZE 9 |
Definition at line 63 of file callback_handlers.hpp.
| bool g_attcoveuler_has_arrived_gpsfix |
For GPSFix: Whether the AttCovEuler block of the current epoch has arrived or not.
Definition at line 714 of file rosaic_node.cpp.
| bool g_attcoveuler_has_arrived_pose |
For PoseWithCovarianceStamped: Whether the AttCovEuler block of the current epoch has arrived or not.
Definition at line 726 of file rosaic_node.cpp.
| bool g_atteuler_has_arrived_gpsfix |
For GPSFix: Whether the AttEuler block of the current epoch has arrived or not.
Definition at line 712 of file rosaic_node.cpp.
| bool g_atteuler_has_arrived_pose |
For PoseWithCovarianceStamped: Whether the AttEuler block of the current epoch has arrived or not.
Definition at line 724 of file rosaic_node.cpp.
| boost::condition_variable g_cd_condition |
Condition variable complementing "g_cd_mutex".
Definition at line 691 of file rosaic_node.cpp.
| uint32_t g_cd_count |
Since after SSSSSSSSSSS we need to wait for second connection descriptor, we have to count the connection descriptors.
Definition at line 698 of file rosaic_node.cpp.
| boost::mutex g_cd_mutex |
Mutex to control changes of global variable "g_cd_received".
Definition at line 687 of file rosaic_node.cpp.
| bool g_cd_received |
Determines whether the connection descriptor was received from the Rx.
Definition at line 689 of file rosaic_node.cpp.
| bool g_channelstatus_has_arrived_gpsfix |
For GPSFix: Whether the ChannelStatus block of the current epoch has arrived or not.
Definition at line 700 of file rosaic_node.cpp.
| bool g_dop_has_arrived_gpsfix |
For GPSFix: Whether the DOP block of the current epoch has arrived or not.
Definition at line 704 of file rosaic_node.cpp.
| bool g_measepoch_has_arrived_gpsfix |
For GPSFix: Whether the MeasEpoch block of the current epoch has arrived or not.
Definition at line 702 of file rosaic_node.cpp.
| bool g_poscovgeodetic_has_arrived_gpsfix |
For GPSFix: Whether the PosCovGeodetic block of the current epoch has arrived or not.
Definition at line 708 of file rosaic_node.cpp.
| bool g_poscovgeodetic_has_arrived_navsatfix |
For NavSatFix: Whether the PosCovGeodetic block of the current epoch has arrived or not.
Definition at line 718 of file rosaic_node.cpp.
| bool g_poscovgeodetic_has_arrived_pose |
For PoseWithCovarianceStamped: Whether the PosCovGeodetic block of the current epoch has arrived or not.
Definition at line 722 of file rosaic_node.cpp.
| bool g_publish_diagnostics |
Whether or not to publish the diagnostic_msgs::DiagnosticArray message.
Definition at line 675 of file rosaic_node.cpp.
| bool g_publish_gpsfix |
Whether or not to publish the gps_common::GPSFix message.
Definition at line 671 of file rosaic_node.cpp.
| bool g_publish_gpst |
Whether or not to publish the sensor_msgs::TimeReference message with GPST.
Definition at line 667 of file rosaic_node.cpp.
| bool g_publish_navsatfix |
Whether or not to publish the sensor_msgs::NavSatFix message.
Definition at line 669 of file rosaic_node.cpp.
| bool g_publish_pose |
Whether or not to publish the geometry_msgs::PoseWithCovarianceStamped message.
Definition at line 673 of file rosaic_node.cpp.
| bool g_pvtgeodetic_has_arrived_gpsfix |
For GPSFix: Whether the PVTGeodetic block of the current epoch has arrived or not.
Definition at line 706 of file rosaic_node.cpp.
| bool g_pvtgeodetic_has_arrived_navsatfix |
For NavSatFix: Whether the PVTGeodetic block of the current epoch has arrived or not.
Definition at line 716 of file rosaic_node.cpp.
| bool g_pvtgeodetic_has_arrived_pose |
For PoseWithCovarianceStamped: Whether the PVTGeodetic block of the current epoch has arrived or not.
Definition at line 720 of file rosaic_node.cpp.
| bool g_qualityind_has_arrived_diagnostics |
For DiagnosticArray: Whether the QualityInd block of the current epoch has arrived or not.
Definition at line 730 of file rosaic_node.cpp.
| bool g_receiverstatus_has_arrived_diagnostics |
For DiagnosticArray: Whether the ReceiverStatus block of the current epoch has arrived or not.
Definition at line 728 of file rosaic_node.cpp.
| boost::condition_variable g_response_condition |
Condition variable complementing "g_response_mutex".
Definition at line 685 of file rosaic_node.cpp.
| boost::mutex g_response_mutex |
Mutex to control changes of global variable "g_response_received".
Definition at line 681 of file rosaic_node.cpp.
| bool g_response_received |
Determines whether a command reply was received from the Rx.
Definition at line 683 of file rosaic_node.cpp.
| std::string g_rx_tcp_port |
Rx TCP port, e.g. IP10 or IP11, to which ROSaic is connected to.
Definition at line 696 of file rosaic_node.cpp.
| bool g_velcovgeodetic_has_arrived_gpsfix |
For GPSFix: Whether the VelCovGeodetic block of the current epoch has arrived or not.
Definition at line 710 of file rosaic_node.cpp.