Implements functions for raw data stream. More...
#include <raw_data_pa.h>
Public Member Functions | |
void | getRosParams (void) |
Get the raw data stream parameters. | |
void | initialize (void) |
Initializes raw data streams If storing to file is enabled, the filename is created and the corresponding filedescriptor will be opened. If publishing ros messages is enabled, an empty msg will be published. (This will implicitly create the publisher) | |
bool | isEnabled (void) |
Returns the if raw data streaming is enabled. | |
void | msgCallback (const std_msgs::UInt8MultiArray::ConstPtr &msg) |
Callback function which handles raw data. | |
RawDataStreamPa (bool is_ros_subscriber=false) | |
Constructor. Initialises variables and the nodehandle. | |
void | ubloxCallback (const unsigned char *data, const std::size_t size) |
Callback function which handles raw data. | |
Private Member Functions | |
void | publishMsg (const std::string str) |
Publishes data stream as ros message. | |
void | saveToFile (const std::string str) |
Stores data to given file. | |
std_msgs::UInt8MultiArray | str2uint8 (const std::string str) |
Converts a string into an uint8 multibyte array. | |
Private Attributes | |
std::string | file_dir_ |
Directoy name for storing raw data. | |
std::ofstream | file_handle_ |
Handle for file access. | |
std::string | file_name_ |
Filename for storing raw data. | |
bool | flag_publish_ |
Flag for publishing raw data. | |
bool | is_ros_subscriber_ |
ros::NodeHandle | nh_ |
ROS node handle (only for subscriber) | |
ros::NodeHandle | pnh_ |
ROS private node handle (for params and publisher) |
Implements functions for raw data stream.
Definition at line 60 of file raw_data_pa.h.
RawDataStreamPa::RawDataStreamPa | ( | bool | is_ros_subscriber = false | ) |
Constructor. Initialises variables and the nodehandle.
Definition at line 50 of file raw_data_pa.cpp.
void RawDataStreamPa::getRosParams | ( | void | ) |
Get the raw data stream parameters.
Definition at line 57 of file raw_data_pa.cpp.
void RawDataStreamPa::initialize | ( | void | ) |
Initializes raw data streams If storing to file is enabled, the filename is created and the corresponding filedescriptor will be opened. If publishing ros messages is enabled, an empty msg will be published. (This will implicitly create the publisher)
Definition at line 77 of file raw_data_pa.cpp.
bool RawDataStreamPa::isEnabled | ( | void | ) |
Returns the if raw data streaming is enabled.
Definition at line 67 of file raw_data_pa.cpp.
void RawDataStreamPa::msgCallback | ( | const std_msgs::UInt8MultiArray::ConstPtr & | msg | ) |
Callback function which handles raw data.
msg | ros message |
Definition at line 148 of file raw_data_pa.cpp.
void RawDataStreamPa::publishMsg | ( | const std::string | str | ) | [private] |
Publishes data stream as ros message.
str | raw data stream as string |
Definition at line 173 of file raw_data_pa.cpp.
void RawDataStreamPa::saveToFile | ( | const std::string | str | ) | [private] |
Stores data to given file.
str | raw data stream as string |
Definition at line 181 of file raw_data_pa.cpp.
std_msgs::UInt8MultiArray RawDataStreamPa::str2uint8 | ( | const std::string | str | ) | [private] |
Converts a string into an uint8 multibyte array.
Definition at line 156 of file raw_data_pa.cpp.
void RawDataStreamPa::ubloxCallback | ( | const unsigned char * | data, |
const std::size_t | size | ||
) |
Callback function which handles raw data.
data | the buffer of u-blox messages to process |
size | the size of the buffer |
Definition at line 136 of file raw_data_pa.cpp.
std::string ublox_node::RawDataStreamPa::file_dir_ [private] |
Directoy name for storing raw data.
Definition at line 122 of file raw_data_pa.h.
std::ofstream ublox_node::RawDataStreamPa::file_handle_ [private] |
Handle for file access.
Definition at line 126 of file raw_data_pa.h.
std::string ublox_node::RawDataStreamPa::file_name_ [private] |
Filename for storing raw data.
Definition at line 124 of file raw_data_pa.h.
bool ublox_node::RawDataStreamPa::flag_publish_ [private] |
Flag for publishing raw data.
Definition at line 129 of file raw_data_pa.h.
bool ublox_node::RawDataStreamPa::is_ros_subscriber_ [private] |
Internal flag true : subscribing to ros messages and storing those to file false: publishing ros messages and/or storing to file
Definition at line 134 of file raw_data_pa.h.
ROS node handle (only for subscriber)
Definition at line 139 of file raw_data_pa.h.
ROS private node handle (for params and publisher)
Definition at line 137 of file raw_data_pa.h.