1 #ifndef ROS_COMPRESSED_STREAMERS_H_ 2 #define ROS_COMPRESSED_STREAMERS_H_ 4 #include <sensor_msgs/CompressedImage.h> 24 virtual void sendImage(
const sensor_msgs::CompressedImageConstPtr &msg,
const ros::Time &time);
27 void imageCallback(
const sensor_msgs::CompressedImageConstPtr &msg);
virtual void restreamFrame(double max_age)
virtual void sendImage(const sensor_msgs::CompressedImageConstPtr &msg, const ros::Time &time)
sensor_msgs::CompressedImageConstPtr last_msg
RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
void imageCallback(const sensor_msgs::CompressedImageConstPtr &msg)
ros::Subscriber image_sub_