The heart of the ROSaic driver: The ROS node that represents it. More...
#include <ros/console.h>#include <boost/regex.hpp>#include <rosaic/communication/communication_core.hpp>

Go to the source code of this file.
Classes | |
| class | rosaic_node::ROSaicNode |
| This class represents the ROsaic node, to be extended.. More... | |
Namespaces | |
| rosaic_node | |
Functions | |
| template<typename V , typename T > | |
| void | rosaic_node::checkRange (V val, T min, T max, std::string name) |
| Checks whether the parameter is in the given range. More... | |
| template<typename V , typename T > | |
| void | rosaic_node::checkRange (std::vector< V > val, T min, T max, std::string name) |
| Check whether the elements of the vector are in the given range. More... | |
| template<typename U > | |
| bool | rosaic_node::getROSInt (const std::string &key, U &u) |
| Gets an integer or unsigned integer value from the parameter server. More... | |
| template<typename U > | |
| void | rosaic_node::getROSInt (const std::string &key, U &u, U default_val) |
| Gets an integer or unsigned integer value from the parameter server. More... | |
| template<typename U > | |
| bool | rosaic_node::getROSInt (const std::string &key, std::vector< U > &u) |
| Gets an unsigned integer or integer vector from the parameter server. More... | |
Variables | |
| boost::shared_ptr< ros::NodeHandle > | g_nh |
| bool | g_publish_attcoveuler |
| bool | g_publish_atteuler |
| bool | g_publish_gpgga |
| 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_poscovcartesian |
| bool | g_publish_poscovgeodetic |
| bool | g_publish_pvtcartesian |
| bool | g_publish_pvtgeodetic |
| ros::Timer | g_reconnect_timer_ |
| const uint32_t | g_ROS_QUEUE_SIZE |
| Queue size for ROS publishers. More... | |
| io_comm_rx::Comm_IO | rosaic_node::IO |
| Handles communication with the Rx. More... | |
The heart of the ROSaic driver: The ROS node that represents it.
Definition in file rosaic_node.hpp.
Node Handle for the ROSaic node You must initialize the NodeHandle in the "main" function (or in any method called indirectly or directly by the main function). One can declare a pointer to the NodeHandle to be a global variable and then initialize it afterwards only...
Definition at line 743 of file rosaic_node.cpp.
| bool g_publish_attcoveuler |
| bool g_publish_atteuler |
| bool g_publish_gpgga |
| 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_poscovcartesian |
| bool g_publish_poscovgeodetic |
| bool g_publish_pvtcartesian |
| bool g_publish_pvtgeodetic |
| ros::Timer g_reconnect_timer_ |
| const uint32_t g_ROS_QUEUE_SIZE |
Queue size for ROS publishers.
Definition at line 745 of file rosaic_node.cpp.