00001 #ifndef ROS_COMPRESSED_STREAMERS_H_ 00002 #define ROS_COMPRESSED_STREAMERS_H_ 00003 00004 #include <sensor_msgs/CompressedImage.h> 00005 #include "web_video_server/image_streamer.h" 00006 #include "async_web_server_cpp/http_request.hpp" 00007 #include "async_web_server_cpp/http_connection.hpp" 00008 #include "web_video_server/multipart_stream.h" 00009 00010 namespace web_video_server 00011 { 00012 00013 class RosCompressedStreamer : public ImageStreamer 00014 { 00015 public: 00016 RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, 00017 ros::NodeHandle& nh); 00018 ~RosCompressedStreamer(); 00019 00020 virtual void start(); 00021 virtual void restreamFrame(double max_age); 00022 00023 protected: 00024 virtual void sendImage(const sensor_msgs::CompressedImageConstPtr &msg, const ros::Time &time); 00025 00026 private: 00027 void imageCallback(const sensor_msgs::CompressedImageConstPtr &msg); 00028 MultipartStream stream_; 00029 ros::Subscriber image_sub_; 00030 ros::Time last_frame; 00031 sensor_msgs::CompressedImageConstPtr last_msg; 00032 boost::mutex send_mutex_; 00033 }; 00034 00035 class RosCompressedStreamerType : public ImageStreamerType 00036 { 00037 public: 00038 boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request, 00039 async_web_server_cpp::HttpConnectionPtr connection, 00040 ros::NodeHandle& nh); 00041 std::string create_viewer(const async_web_server_cpp::HttpRequest &request); 00042 }; 00043 00044 } 00045 00046 #endif