1 #ifndef IMAGE_STREAMER_H_ 2 #define IMAGE_STREAMER_H_ 6 #include <opencv2/opencv.hpp> 7 #include "async_web_server_cpp/http_server.hpp" 8 #include "async_web_server_cpp/http_request.hpp" 16 ImageStreamer(
const async_web_server_cpp::HttpRequest &request,
17 async_web_server_cpp::HttpConnectionPtr connection,
20 virtual void start() = 0;
40 async_web_server_cpp::HttpConnectionPtr
connection_;
58 virtual void sendImage(
const cv::Mat &,
const ros::Time &time) = 0;
83 async_web_server_cpp::HttpConnectionPtr connection,
86 virtual std::string create_viewer(
const async_web_server_cpp::HttpRequest &request) = 0;
async_web_server_cpp::HttpConnectionPtr connection_
ROSCONSOLE_DECL void initialize()
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
virtual void restreamFrame(double max_age)=0
async_web_server_cpp::HttpRequest request_
cv::Mat output_size_image
image_transport::ImageTransport it_
std::string default_transport_
ImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
image_transport::Subscriber image_sub_
image_transport::Subscriber image_sub_