Skip to content

Commit ffdf25c

Browse files
authored
Sync ROS 2 branch up to version 0.2.1 (#95)
* fix SteadyTimer check for backported ROS versions (#71) i.e. on current kinetic * Add PngStreamer (#74) * lax rule for topic name (#77) * Add a workaround for MultipartStream constant busy state (#83) * Add a workaround for MultipartStream constant busy state * Remove C++11 features * Add "default_stream_type" parameter (#84) This allows users to specify default stream type in their .launch files. Using a "ros_compressed" stream type sometimes results in a much lower resource consumption, and having it set as a default is much nicer for end users. * update changelog * 0.2.0 * Fall back to mjpeg if ros_compressed is unavailable (#87) * Update travis config (#89) * Restream buffered frames with minimum publish rate (#88) * Restream buffered frames with minimum publish rate * Implement restreaming for ros_compressed_streamer * update changelog * 0.2.1
1 parent 84b410b commit ffdf25c

15 files changed

+411
-32
lines changed

CHANGELOG.rst

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,33 @@
22
Changelog for package web_video_server
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
0.2.1 (2019-06-05)
6+
------------------
7+
* Restream buffered frames with minimum publish rate (`#88 <https://github.com/RobotWebTools/web_video_server/issues/88>`_)
8+
* Restream buffered frames with minimum publish rate
9+
* Implement restreaming for ros_compressed_streamer
10+
* Update travis config (`#89 <https://github.com/RobotWebTools/web_video_server/issues/89>`_)
11+
* Fall back to mjpeg if ros_compressed is unavailable (`#87 <https://github.com/RobotWebTools/web_video_server/issues/87>`_)
12+
* Contributors: Jihoon Lee, Viktor Kunovski, sfalexrog
13+
14+
0.2.0 (2019-01-30)
15+
------------------
16+
* Add "default_stream_type" parameter (`#84 <https://github.com/RobotWebTools/web_video_server/issues/84>`_)
17+
This allows users to specify default stream type in their .launch files. Using a "ros_compressed" stream type sometimes
18+
results in a much lower resource consumption, and having it set as a default is much nicer for end users.
19+
* Add a workaround for MultipartStream constant busy state (`#83 <https://github.com/RobotWebTools/web_video_server/issues/83>`_)
20+
* Add a workaround for MultipartStream constant busy state
21+
* Remove C++11 features
22+
* lax rule for topic name (`#77 <https://github.com/RobotWebTools/web_video_server/issues/77>`_)
23+
* Add PngStreamer (`#74 <https://github.com/RobotWebTools/web_video_server/issues/74>`_)
24+
* fix SteadyTimer check for backported ROS versions (`#71 <https://github.com/RobotWebTools/web_video_server/issues/71>`_)
25+
i.e. on current kinetic
26+
* Pkg format 2 (`#68 <https://github.com/RobotWebTools/web_video_server/issues/68>`_)
27+
* use package format 2
28+
* add missing dependency on sensor_msgs
29+
* fixed undeclared CODEC_FLAG_GLOBAL_HEADER (`#65 <https://github.com/RobotWebTools/web_video_server/issues/65>`_)
30+
* Contributors: Andreas Klintberg, Dirk Thomas, Felix Ruess, Kazuto Murase, Viktor Kunovski, sfalexrog
31+
532
0.1.0 (2018-07-01)
633
------------------
734
* Avoid queuing of images on slow ethernet connection (`#64 <https://github.com/RobotWebTools/web_video_server/issues/64>`_)

CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,9 @@ add_executable(${PROJECT_NAME}
4949
src/vp9_streamer.cpp
5050
src/multipart_stream.cpp
5151
src/ros_compressed_streamer.cpp
52-
src/jpeg_streamers.cpp)
52+
src/jpeg_streamers.cpp
53+
src/png_streamers.cpp
54+
)
5355

5456
ament_target_dependencies(${PROJECT_NAME}
5557
async_web_server_cpp cv_bridge image_transport rclcpp sensor_msgs)

include/web_video_server/image_streamer.h

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,13 +19,19 @@ class ImageStreamer
1919
rclcpp::Node::SharedPtr nh);
2020

2121
virtual void start() = 0;
22+
virtual ~ImageStreamer();
2223

2324
bool isInactive()
2425
{
2526
return inactive_;
2627
}
2728
;
2829

30+
/**
31+
* Restreams the last received image frame if older than max_age.
32+
*/
33+
virtual void restreamFrame(double max_age) = 0;
34+
2935
std::string getTopic()
3036
{
3137
return topic_;
@@ -46,19 +52,25 @@ class ImageTransportImageStreamer : public ImageStreamer
4652
public:
4753
ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
4854
rclcpp::Node::SharedPtr nh);
55+
virtual ~ImageTransportImageStreamer();
4956

5057
virtual void start();
5158

5259
protected:
5360
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time) = 0;
54-
61+
virtual void restreamFrame(double max_age);
5562
virtual void initialize(const cv::Mat &);
5663

5764
image_transport::Subscriber image_sub_;
5865
int output_width_;
5966
int output_height_;
6067
bool invert_;
6168
std::string default_transport_;
69+
70+
rclcpp::Time last_frame;
71+
cv::Mat output_size_image;
72+
boost::mutex send_mutex_;
73+
6274
private:
6375
image_transport::ImageTransport it_;
6476
bool initialized_;

include/web_video_server/jpeg_streamers.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ class MjpegStreamer : public ImageTransportImageStreamer
1515
public:
1616
MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
1717
rclcpp::Node::SharedPtr nh);
18-
18+
~MjpegStreamer();
1919
protected:
2020
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
2121

@@ -38,7 +38,7 @@ class JpegSnapshotStreamer : public ImageTransportImageStreamer
3838
public:
3939
JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request,
4040
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh);
41-
41+
~JpegSnapshotStreamer();
4242
protected:
4343
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
4444

include/web_video_server/multipart_stream.h

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,15 +9,21 @@
99
namespace web_video_server
1010
{
1111

12+
struct PendingFooter {
13+
rclcpp::Time timestamp;
14+
std::weak_ptr<std::string> contents;
15+
};
16+
1217
class MultipartStream {
1318
public:
14-
MultipartStream(async_web_server_cpp::HttpConnectionPtr& connection,
19+
MultipartStream(std::function<rclcpp::Time()> get_now,
20+
async_web_server_cpp::HttpConnectionPtr& connection,
1521
const std::string& boundry="boundarydonotcross",
1622
std::size_t max_queue_size=1);
1723

1824
void sendInitialHeader();
1925
void sendPartHeader(const rclcpp::Time &time, const std::string& type, size_t payload_size);
20-
void sendPartFooter();
26+
void sendPartFooter(const rclcpp::Time &time);
2127
void sendPartAndClear(const rclcpp::Time &time, const std::string& type, std::vector<unsigned char> &data);
2228
void sendPart(const rclcpp::Time &time, const std::string& type, const boost::asio::const_buffer &buffer,
2329
async_web_server_cpp::HttpConnection::ResourcePtr resource);
@@ -26,10 +32,11 @@ class MultipartStream {
2632
bool isBusy();
2733

2834
private:
35+
std::function<rclcpp::Time()> get_now_;
2936
const std::size_t max_queue_size_;
3037
async_web_server_cpp::HttpConnectionPtr connection_;
3138
std::string boundry_;
32-
std::queue<std::weak_ptr<const void> > pending_footers_;
39+
std::queue<PendingFooter> pending_footers_;
3340
};
3441

3542
}
Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
#ifndef PNG_STREAMERS_H_
2+
#define PNG_STREAMERS_H_
3+
4+
#include <image_transport/image_transport.h>
5+
#include "web_video_server/image_streamer.h"
6+
#include "async_web_server_cpp/http_request.hpp"
7+
#include "async_web_server_cpp/http_connection.hpp"
8+
#include "web_video_server/multipart_stream.h"
9+
10+
namespace web_video_server
11+
{
12+
13+
class PngStreamer : public ImageTransportImageStreamer
14+
{
15+
public:
16+
PngStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
17+
rclcpp::Node::SharedPtr nh);
18+
~PngStreamer();
19+
protected:
20+
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
21+
22+
private:
23+
MultipartStream stream_;
24+
int quality_;
25+
};
26+
27+
class PngStreamerType : public ImageStreamerType
28+
{
29+
public:
30+
boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
31+
async_web_server_cpp::HttpConnectionPtr connection,
32+
rclcpp::Node::SharedPtr nh);
33+
std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
34+
};
35+
36+
class PngSnapshotStreamer : public ImageTransportImageStreamer
37+
{
38+
public:
39+
PngSnapshotStreamer(const async_web_server_cpp::HttpRequest &request,
40+
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh);
41+
~PngSnapshotStreamer();
42+
protected:
43+
virtual void sendImage(const cv::Mat &, const rclcpp::Time &time);
44+
45+
private:
46+
int quality_;
47+
};
48+
49+
}
50+
51+
#endif

include/web_video_server/ros_compressed_streamer.h

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,20 @@ class RosCompressedStreamer : public ImageStreamer
1515
public:
1616
RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
1717
rclcpp::Node::SharedPtr nh);
18+
~RosCompressedStreamer();
1819
virtual void start();
20+
virtual void restreamFrame(double max_age);
21+
22+
protected:
23+
virtual void sendImage(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg, const rclcpp::Time &time);
1924

2025
private:
2126
void imageCallback(const sensor_msgs::msg::CompressedImage::ConstSharedPtr msg);
22-
2327
MultipartStream stream_;
2428
rclcpp::Subscription<sensor_msgs::msg::CompressedImage>::SharedPtr image_sub_;
29+
rclcpp::Time last_frame;
30+
sensor_msgs::msg::CompressedImage::ConstSharedPtr last_msg;
31+
boost::mutex send_mutex_;
2532
};
2633

2734
class RosCompressedStreamerType : public ImageStreamerType

include/web_video_server/web_video_server.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,11 +50,13 @@ class WebVideoServer
5050
async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
5151

5252
private:
53+
void restreamFrames(double max_age);
5354
void cleanup_inactive_streams();
5455

5556
rclcpp::Node::SharedPtr nh_;
5657
rclcpp::WallTimer<rclcpp::VoidCallbackType>::SharedPtr cleanup_timer_;
5758
int ros_threads_;
59+
double publish_rate_;
5860
int port_;
5961
std::string address_;
6062
boost::shared_ptr<async_web_server_cpp::HttpServer> server_;

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>web_video_server</name>
4-
<version>0.1.0</version>
4+
<version>0.2.1</version>
55
<description>HTTP Streaming of ROS Image Topics in Multiple Formats</description>
66

77
<maintainer email="[email protected]">Russell Toris</maintainer>

src/image_streamer.cpp

Lines changed: 47 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
#include "web_video_server/image_streamer.h"
22
#include <cv_bridge/cv_bridge.h>
3+
#include <iostream>
34

45
namespace web_video_server
56
{
@@ -11,6 +12,10 @@ ImageStreamer::ImageStreamer(const async_web_server_cpp::HttpRequest &request,
1112
topic_ = request.get_query_param_value_or_default("topic", "");
1213
}
1314

15+
ImageStreamer::~ImageStreamer()
16+
{
17+
}
18+
1419
ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request,
1520
async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh) :
1621
ImageStreamer(request, connection, nh), it_(nh), initialized_(false)
@@ -21,6 +26,10 @@ ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_
2126
default_transport_ = request.get_query_param_value_or_default("default_transport", "raw");
2227
}
2328

29+
ImageTransportImageStreamer::~ImageTransportImageStreamer()
30+
{
31+
}
32+
2433
void ImageTransportImageStreamer::start()
2534
{
2635
image_transport::TransportHints hints(nh_.get(), default_transport_);
@@ -32,7 +41,7 @@ void ImageTransportImageStreamer::start()
3241
break;
3342
}
3443
auto & topic_name = topic_and_types.first;
35-
if(topic_name == topic_){
44+
if(topic_name == topic_ || (topic_name.find("/") == 0 && topic_name.substr(1) == topic_)){
3645
inactive_ = false;
3746
break;
3847
}
@@ -44,6 +53,39 @@ void ImageTransportImageStreamer::initialize(const cv::Mat &)
4453
{
4554
}
4655

56+
void ImageTransportImageStreamer::restreamFrame(double max_age)
57+
{
58+
if (inactive_ || !initialized_ )
59+
return;
60+
try {
61+
if ( last_frame + rclcpp::Duration(max_age) < nh_->now() ) {
62+
boost::mutex::scoped_lock lock(send_mutex_);
63+
sendImage(output_size_image, nh_->now() ); // don't update last_frame, it may remain an old value.
64+
}
65+
}
66+
catch (boost::system::system_error &e)
67+
{
68+
// happens when client disconnects
69+
RCLCPP_DEBUG(nh_->get_logger(), "system_error exception: %s", e.what());
70+
inactive_ = true;
71+
return;
72+
}
73+
catch (std::exception &e)
74+
{
75+
// TODO THROTTLE with 30
76+
RCLCPP_ERROR(nh_->get_logger(), "exception: %s", e.what());
77+
inactive_ = true;
78+
return;
79+
}
80+
catch (...)
81+
{
82+
// TODO THROTTLE with 30
83+
RCLCPP_ERROR(nh_->get_logger(), "exception");
84+
inactive_ = true;
85+
return;
86+
}
87+
}
88+
4789
void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr &msg)
4890
{
4991
if (inactive_)
@@ -87,7 +129,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C
87129
cv::flip(img, img, true);
88130
}
89131

90-
cv::Mat output_size_image;
132+
boost::mutex::scoped_lock lock(send_mutex_); // protects output_size_image
91133
if (output_width_ != input_width || output_height_ != input_height)
92134
{
93135
cv::Mat img_resized;
@@ -105,7 +147,9 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C
105147
initialize(output_size_image);
106148
initialized_ = true;
107149
}
108-
sendImage(output_size_image, msg->header.stamp);
150+
151+
last_frame = nh_->now();
152+
sendImage(output_size_image, last_frame );
109153

110154
}
111155
catch (cv_bridge::Exception &e)

0 commit comments

Comments
 (0)