11#include " web_video_server/ros_compressed_streamer.h"
22
3+ #include < dynamic_reconfigure/IntParameter.h>
4+ #include < dynamic_reconfigure/StrParameter.h>
5+ #include < dynamic_reconfigure/Reconfigure.h>
6+ #include < dynamic_reconfigure/Config.h>
7+
38namespace web_video_server
49{
510
11+ const int PARAM_NO_CHANGE_INT = -1 ;
12+
613RosCompressedStreamer::RosCompressedStreamer (const async_web_server_cpp::HttpRequest &request,
714 async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) :
815 ImageStreamer (request, connection, nh), stream_(connection)
916{
17+ jpeg_quality_ = request.get_query_param_value_or_default <int >(" quality" , PARAM_NO_CHANGE_INT);
18+ png_level_ = request.get_query_param_value_or_default <int >(" level" , PARAM_NO_CHANGE_INT);
19+ format_ = request.get_query_param_value_or_default <std::string>(" format" , " " );
20+
1021 stream_.sendInitialHeader ();
1122}
1223
@@ -18,6 +29,7 @@ RosCompressedStreamer::~RosCompressedStreamer()
1829
1930void RosCompressedStreamer::start () {
2031 std::string compressed_topic = topic_ + " /compressed" ;
32+ updateImageParameters ();
2133 image_sub_ = nh_.subscribe (compressed_topic, 1 , &RosCompressedStreamer::imageCallback, this );
2234}
2335
@@ -79,6 +91,40 @@ void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageCons
7991}
8092
8193
94+ void RosCompressedStreamer::updateImageParameters ()
95+ {
96+ dynamic_reconfigure::Config reconf_config;
97+ if (jpeg_quality_ > 0 && jpeg_quality_ <= 100 ) {
98+ dynamic_reconfigure::IntParameter param;
99+ param.name = " jpeg_quality" ;
100+ param.value = jpeg_quality_;
101+ ROS_DEBUG (" setting jpeg quality to %d for topic %s" , jpeg_quality_, topic_.c_str ());
102+ reconf_config.ints .push_back (param);
103+ }
104+ if (png_level_ > 0 && png_level_ <= 9 ) {
105+ dynamic_reconfigure::IntParameter param;
106+ param.name = " png_level" ;
107+ param.value = png_level_;
108+ ROS_DEBUG (" setting png compression level to %d for topic %s" , png_level_, topic_.c_str ());
109+ reconf_config.ints .push_back (param);
110+ }
111+ if (format_ == " jpeg" || format_ == " png" ) { // Only allow jpeg/png compression
112+ dynamic_reconfigure::StrParameter param;
113+ param.name = " format" ;
114+ param.value = format_;
115+ ROS_DEBUG (" setting compression format to %s for topic %s" , format_.c_str (), topic_.c_str ());
116+ reconf_config.strs .push_back (param);
117+ }
118+ if (reconf_config.ints .size () > 0 || reconf_config.strs .size () > 0 )
119+ {
120+ dynamic_reconfigure::ReconfigureRequest reconf_request;
121+ dynamic_reconfigure::ReconfigureResponse reconf_response;
122+ reconf_request.config = reconf_config;
123+ ROS_DEBUG (" applying settings for %s" , format_.c_str ());
124+ ros::service::call (topic_ + " /compressed/set_parameters" , reconf_request, reconf_response);
125+ }
126+ }
127+
82128boost::shared_ptr<ImageStreamer> RosCompressedStreamerType::create_streamer (const async_web_server_cpp::HttpRequest &request,
83129 async_web_server_cpp::HttpConnectionPtr connection,
84130 ros::NodeHandle& nh)
0 commit comments