ros_compressed_streamer.h
Go to the documentation of this file.
1 #ifndef ROS_COMPRESSED_STREAMERS_H_
2 #define ROS_COMPRESSED_STREAMERS_H_
3 
4 #include <sensor_msgs/CompressedImage.h>
9 
10 namespace web_video_server
11 {
12 
14 {
15 public:
17  ros::NodeHandle& nh);
19 
20  virtual void start();
21  virtual void restreamFrame(double max_age);
22 
23 protected:
24  virtual void sendImage(const sensor_msgs::CompressedImageConstPtr &msg, const ros::Time &time);
25 
26 private:
27  void imageCallback(const sensor_msgs::CompressedImageConstPtr &msg);
31  sensor_msgs::CompressedImageConstPtr last_msg;
32  boost::mutex send_mutex_;
33 };
34 
36 {
37 public:
40  ros::NodeHandle& nh);
41  std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
42 };
43 
44 }
45 
46 #endif
web_video_server::ImageStreamer
Definition: image_streamer.h:13
web_video_server::RosCompressedStreamerType
Definition: ros_compressed_streamer.h:35
boost::shared_ptr< HttpConnection >
web_video_server::RosCompressedStreamer::last_msg
sensor_msgs::CompressedImageConstPtr last_msg
Definition: ros_compressed_streamer.h:31
image_streamer.h
web_video_server::ImageStreamerType
Definition: image_streamer.h:79
web_video_server::RosCompressedStreamer::sendImage
virtual void sendImage(const sensor_msgs::CompressedImageConstPtr &msg, const ros::Time &time)
Definition: ros_compressed_streamer.cpp:35
web_video_server::RosCompressedStreamer::restreamFrame
virtual void restreamFrame(double max_age)
Definition: ros_compressed_streamer.cpp:24
web_video_server::RosCompressedStreamer::imageCallback
void imageCallback(const sensor_msgs::CompressedImageConstPtr &msg)
Definition: ros_compressed_streamer.cpp:74
web_video_server::RosCompressedStreamer
Definition: ros_compressed_streamer.h:13
web_video_server::RosCompressedStreamer::RosCompressedStreamer
RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
Definition: ros_compressed_streamer.cpp:6
async_web_server_cpp::HttpRequest
web_video_server::RosCompressedStreamer::~RosCompressedStreamer
~RosCompressedStreamer()
Definition: ros_compressed_streamer.cpp:13
web_video_server::RosCompressedStreamer::last_frame
ros::Time last_frame
Definition: ros_compressed_streamer.h:30
http_connection.hpp
web_video_server
Definition: h264_streamer.h:9
web_video_server::RosCompressedStreamer::image_sub_
ros::Subscriber image_sub_
Definition: ros_compressed_streamer.h:29
ros::Time
web_video_server::RosCompressedStreamer::stream_
MultipartStream stream_
Definition: ros_compressed_streamer.h:28
web_video_server::RosCompressedStreamerType::create_viewer
std::string create_viewer(const async_web_server_cpp::HttpRequest &request)
Definition: ros_compressed_streamer.cpp:89
http_request.hpp
web_video_server::RosCompressedStreamer::send_mutex_
boost::mutex send_mutex_
Definition: ros_compressed_streamer.h:32
web_video_server::RosCompressedStreamer::start
virtual void start()
Definition: ros_compressed_streamer.cpp:19
multipart_stream.h
web_video_server::RosCompressedStreamerType::create_streamer
boost::shared_ptr< ImageStreamer > create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
Definition: ros_compressed_streamer.cpp:82
web_video_server::MultipartStream
Definition: multipart_stream.h:17
ros::NodeHandle
ros::Subscriber


web_video_server
Author(s): Mitchell Wills
autogenerated on Wed Mar 2 2022 01:13:35