forked from RobotWebTools/web_video_server
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathros_compressed_streamer.h
46 lines (37 loc) · 1.41 KB
/
ros_compressed_streamer.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
#ifndef ROS_COMPRESSED_STREAMERS_H_
#define ROS_COMPRESSED_STREAMERS_H_
#include <sensor_msgs/CompressedImage.h>
#include "web_video_server/image_streamer.h"
#include "async_web_server_cpp/http_request.hpp"
#include "async_web_server_cpp/http_connection.hpp"
#include "web_video_server/multipart_stream.h"
namespace web_video_server
{
class RosCompressedStreamer : public ImageStreamer
{
public:
RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
ros::NodeHandle& nh);
~RosCompressedStreamer();
virtual void start();
virtual void restreamFrame(double max_age);
protected:
virtual void sendImage(const sensor_msgs::CompressedImageConstPtr &msg, const ros::Time &time);
private:
void imageCallback(const sensor_msgs::CompressedImageConstPtr &msg);
MultipartStream stream_;
ros::Subscriber image_sub_;
ros::Time last_frame;
sensor_msgs::CompressedImageConstPtr last_msg;
boost::mutex send_mutex_;
};
class RosCompressedStreamerType : public ImageStreamerType
{
public:
boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
ros::NodeHandle& nh);
std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
};
}
#endif