ros_compressed_streamer.cpp
Go to the documentation of this file.
2 
3 namespace web_video_server
4 {
5 
8  ImageStreamer(request, connection, nh), stream_(connection)
9 {
11 }
12 
14 {
15  this->inactive_ = true;
16  boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
17 }
18 
20  std::string compressed_topic = topic_ + "/compressed";
21  image_sub_ = nh_.subscribe(compressed_topic, 1, &RosCompressedStreamer::imageCallback, this);
22 }
23 
25 {
26  if (inactive_ || (last_msg == 0))
27  return;
28 
29  if ( last_frame + ros::Duration(max_age) < ros::Time::now() ) {
30  boost::mutex::scoped_lock lock(send_mutex_);
31  sendImage(last_msg, ros::Time::now() ); // don't update last_frame, it may remain an old value.
32  }
33 }
34 
35 void RosCompressedStreamer::sendImage(const sensor_msgs::CompressedImageConstPtr &msg,
36  const ros::Time &time) {
37  try {
38  std::string content_type;
39  if(msg->format.find("jpeg") != std::string::npos) {
40  content_type = "image/jpeg";
41  }
42  else if(msg->format.find("png") != std::string::npos) {
43  content_type = "image/png";
44  }
45  else {
46  ROS_WARN_STREAM("Unknown ROS compressed image format: " << msg->format);
47  return;
48  }
49 
50  stream_.sendPart(time, content_type, boost::asio::buffer(msg->data), msg);
51  }
52  catch (boost::system::system_error &e)
53  {
54  // happens when client disconnects
55  ROS_DEBUG("system_error exception: %s", e.what());
56  inactive_ = true;
57  return;
58  }
59  catch (std::exception &e)
60  {
61  ROS_ERROR_THROTTLE(30, "exception: %s", e.what());
62  inactive_ = true;
63  return;
64  }
65  catch (...)
66  {
67  ROS_ERROR_THROTTLE(30, "exception");
68  inactive_ = true;
69  return;
70  }
71 }
72 
73 
74 void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageConstPtr &msg) {
75  boost::mutex::scoped_lock lock(send_mutex_); // protects last_msg and last_frame
76  last_msg = msg;
77  last_frame = ros::Time(msg->header.stamp.sec, msg->header.stamp.nsec);
79 }
80 
81 
84  ros::NodeHandle& nh)
85 {
86  return boost::shared_ptr<ImageStreamer>(new RosCompressedStreamer(request, connection, nh));
87 }
88 
90 {
91  std::stringstream ss;
92  ss << "<img src=\"/stream?";
93  ss << request.query;
94  ss << "\"></img>";
95  return ss.str();
96 }
97 
98 
99 }
ros_compressed_streamer.h
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
web_video_server::ImageStreamer
Definition: image_streamer.h:13
boost::shared_ptr< HttpConnection >
web_video_server::ImageStreamer::inactive_
bool inactive_
Definition: image_streamer.h:43
web_video_server::RosCompressedStreamer::last_msg
sensor_msgs::CompressedImageConstPtr last_msg
Definition: ros_compressed_streamer.h:31
web_video_server::MultipartStream::sendPart
void sendPart(const ros::Time &time, const std::string &type, const boost::asio::const_buffer &buffer, async_web_server_cpp::HttpConnection::ResourcePtr resource)
Definition: multipart_stream.cpp:54
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::MultipartStream::sendInitialHeader
void sendInitialHeader()
Definition: multipart_stream.cpp:14
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
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
web_video_server::ImageStreamer::topic_
std::string topic_
Definition: image_streamer.h:45
ROS_DEBUG
#define ROS_DEBUG(...)
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
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
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::ImageStreamer::nh_
ros::NodeHandle nh_
Definition: image_streamer.h:42
async_web_server_cpp::HttpRequest::query
std::string query
web_video_server::RosCompressedStreamerType::create_viewer
std::string create_viewer(const async_web_server_cpp::HttpRequest &request)
Definition: ros_compressed_streamer.cpp:89
web_video_server::RosCompressedStreamer::send_mutex_
boost::mutex send_mutex_
Definition: ros_compressed_streamer.h:32
ros::Duration
web_video_server::RosCompressedStreamer::start
virtual void start()
Definition: ros_compressed_streamer.cpp:19
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
ros::NodeHandle
ros::Time::now
static Time now()


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