Skip to content

ros_compressed: Reconfigure compressed topic from request #96

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 2 commits into
base: ros1
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ project(web_video_server)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp roslib cv_bridge image_transport async_web_server_cpp sensor_msgs)
find_package(catkin REQUIRED COMPONENTS roscpp roslib cv_bridge image_transport async_web_server_cpp sensor_msgs dynamic_reconfigure)
find_package(OpenCV REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread)

Expand Down
5 changes: 5 additions & 0 deletions include/web_video_server/ros_compressed_streamer.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,16 @@ class RosCompressedStreamer : public ImageStreamer

private:
void imageCallback(const sensor_msgs::CompressedImageConstPtr &msg);
void updateImageParameters();
MultipartStream stream_;
ros::Subscriber image_sub_;
ros::Time last_frame;
sensor_msgs::CompressedImageConstPtr last_msg;
boost::mutex send_mutex_;

int jpeg_quality_;
int png_level_;
std::string format_;
};

class RosCompressedStreamerType : public ImageStreamerType
Expand Down
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<build_depend>async_web_server_cpp</build_depend>
<build_depend>ffmpeg</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>dynamic_reconfigure</build_depend>

<exec_depend>roscpp</exec_depend>
<exec_depend>roslib</exec_depend>
Expand All @@ -32,4 +33,5 @@
<exec_depend>async_web_server_cpp</exec_depend>
<exec_depend>ffmpeg</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>dynamic_reconfigure</exec_depend>
</package>
46 changes: 46 additions & 0 deletions src/ros_compressed_streamer.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,23 @@
#include "web_video_server/ros_compressed_streamer.h"

#include <dynamic_reconfigure/IntParameter.h>
#include <dynamic_reconfigure/StrParameter.h>
#include <dynamic_reconfigure/Reconfigure.h>
#include <dynamic_reconfigure/Config.h>

namespace web_video_server
{

const int PARAM_NO_CHANGE_INT = -1;

RosCompressedStreamer::RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) :
ImageStreamer(request, connection, nh), stream_(connection)
{
jpeg_quality_ = request.get_query_param_value_or_default<int>("quality", PARAM_NO_CHANGE_INT);
png_level_ = request.get_query_param_value_or_default<int>("level", PARAM_NO_CHANGE_INT);
format_ = request.get_query_param_value_or_default<std::string>("format", "");

stream_.sendInitialHeader();
}

Expand All @@ -18,6 +29,7 @@ RosCompressedStreamer::~RosCompressedStreamer()

void RosCompressedStreamer::start() {
std::string compressed_topic = topic_ + "/compressed";
updateImageParameters();
image_sub_ = nh_.subscribe(compressed_topic, 1, &RosCompressedStreamer::imageCallback, this);
}

Expand Down Expand Up @@ -79,6 +91,40 @@ void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageCons
}


void RosCompressedStreamer::updateImageParameters()
{
dynamic_reconfigure::Config reconf_config;
if (jpeg_quality_ > 0 && jpeg_quality_ <= 100) {
dynamic_reconfigure::IntParameter param;
param.name = "jpeg_quality";
param.value = jpeg_quality_;
ROS_DEBUG("setting jpeg quality to %d for topic %s", jpeg_quality_, topic_.c_str());
reconf_config.ints.push_back(param);
}
if (png_level_ > 0 && png_level_ <= 9) {
dynamic_reconfigure::IntParameter param;
param.name = "png_level";
param.value = png_level_;
ROS_DEBUG("setting png compression level to %d for topic %s", png_level_, topic_.c_str());
reconf_config.ints.push_back(param);
}
if (format_ == "jpeg" || format_ == "png") { // Only allow jpeg/png compression
dynamic_reconfigure::StrParameter param;
param.name = "format";
param.value = format_;
ROS_DEBUG("setting compression format to %s for topic %s", format_.c_str(), topic_.c_str());
reconf_config.strs.push_back(param);
}
if (reconf_config.ints.size() > 0 || reconf_config.strs.size() > 0)
{
dynamic_reconfigure::ReconfigureRequest reconf_request;
dynamic_reconfigure::ReconfigureResponse reconf_response;
reconf_request.config = reconf_config;
ROS_DEBUG("applying settings for %s", format_.c_str());
ros::service::call(topic_ + "/compressed/set_parameters", reconf_request, reconf_response);
}
}

boost::shared_ptr<ImageStreamer> RosCompressedStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request,
async_web_server_cpp::HttpConnectionPtr connection,
ros::NodeHandle& nh)
Expand Down