36 #ifndef UBLOX_RAW_DATA_PA_H 37 #define UBLOX_RAW_DATA_PA_H 48 #include <std_msgs/UInt8MultiArray.h> 95 const std::size_t size);
107 std_msgs::UInt8MultiArray
str2uint8(
const std::string str);
Implements functions for raw data stream.
void ubloxCallback(const unsigned char *data, const std::size_t size)
Callback function which handles raw data.
void saveToFile(const std::string str)
Stores data to given file.
std::string file_dir_
Directoy name for storing raw data.
bool flag_publish_
Flag for publishing raw data.
std_msgs::UInt8MultiArray str2uint8(const std::string str)
Converts a string into an uint8 multibyte array.
ros::NodeHandle nh_
ROS node handle (only for subscriber)
void initialize(void)
Initializes raw data streams If storing to file is enabled, the filename is created and the correspon...
std::ofstream file_handle_
Handle for file access.
ros::NodeHandle pnh_
ROS private node handle (for params and publisher)
RawDataStreamPa(bool is_ros_subscriber=false)
Constructor. Initialises variables and the nodehandle.
void publishMsg(const std::string str)
Publishes data stream as ros message.
std::string file_name_
Filename for storing raw data.
void msgCallback(const std_msgs::UInt8MultiArray::ConstPtr &msg)
Callback function which handles raw data.
bool isEnabled(void)
Returns the if raw data streaming is enabled.
void getRosParams(void)
Get the raw data stream parameters.