19 #ifndef DDS_ROS_BRIDGE_ROS_COMPRESSED_IMAGE_RAPID_IMAGE_H_
20 #define DDS_ROS_BRIDGE_ROS_COMPRESSED_IMAGE_RAPID_IMAGE_H_
24 #include "dds_ros_bridge/ros_sub_rapid_pub.h"
26 #include "rapidDds/MIMETypesConstants.h"
27 #include "rapidDds/RapidConstants.h"
29 #include "rapidIo/ImageSensorProvider.h"
30 #include "rapidIo/RapidIoParameters.h"
32 #include "sensor_msgs/CompressedImage.h"
43 const std::string& pub_topic,
44 const ros::NodeHandle &nh,
45 const unsigned int queue_size = 10);
47 void CallBack(
const sensor_msgs::CompressedImage::ConstPtr& msg);
50 std::string GetRapidMimeType(
const std::string& ros_format);
51 rapid::ImageSensorProviderParameters params_;
52 std::shared_ptr<rapid::ImageSensorProvider> provider_;
53 const unsigned int MB_;
58 #endif // DDS_ROS_BRIDGE_ROS_COMPRESSED_IMAGE_RAPID_IMAGE_H_