Public Member Functions | Private Member Functions | Private Attributes | List of all members
ublox_node::RawDataStreamPa Class Reference

Implements functions for raw data stream. More...

#include <raw_data_pa.h>

Public Member Functions

void getRosParams (void)
 Get the raw data stream parameters. More...
 
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) More...
 
bool isEnabled (void)
 Returns the if raw data streaming is enabled. More...
 
void msgCallback (const std_msgs::UInt8MultiArray::ConstPtr &msg)
 Callback function which handles raw data. More...
 
 RawDataStreamPa (bool is_ros_subscriber=false)
 Constructor. Initialises variables and the nodehandle. More...
 
void ubloxCallback (const unsigned char *data, const std::size_t size)
 Callback function which handles raw data. More...
 

Private Member Functions

void publishMsg (const std::string str)
 Publishes data stream as ros message. More...
 
void saveToFile (const std::string str)
 Stores data to given file. More...
 
std_msgs::UInt8MultiArray str2uint8 (const std::string str)
 Converts a string into an uint8 multibyte array. More...
 

Private Attributes

std::string file_dir_
 Directoy name for storing raw data. More...
 
std::ofstream file_handle_
 Handle for file access. More...
 
std::string file_name_
 Filename for storing raw data. More...
 
bool flag_publish_
 Flag for publishing raw data. More...
 
bool is_ros_subscriber_
 
ros::NodeHandle nh_
 ROS node handle (only for subscriber) More...
 
ros::NodeHandle pnh_
 ROS private node handle (for params and publisher) More...
 

Detailed Description

Implements functions for raw data stream.

Definition at line 60 of file raw_data_pa.h.

Constructor & Destructor Documentation

RawDataStreamPa::RawDataStreamPa ( bool  is_ros_subscriber = false)

Constructor. Initialises variables and the nodehandle.

Definition at line 50 of file raw_data_pa.cpp.

Member Function Documentation

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.

Parameters
msgros 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.

Parameters
strraw 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.

Parameters
strraw 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.

Parameters
datathe buffer of u-blox messages to process
sizethe size of the buffer

Definition at line 136 of file raw_data_pa.cpp.

Member Data Documentation

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::NodeHandle ublox_node::RawDataStreamPa::nh_
private

ROS node handle (only for subscriber)

Definition at line 139 of file raw_data_pa.h.

ros::NodeHandle ublox_node::RawDataStreamPa::pnh_
private

ROS private node handle (for params and publisher)

Definition at line 137 of file raw_data_pa.h.


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


ublox_gps
Author(s): Johannes Meyer
autogenerated on Thu Jan 28 2021 03:13:52