Go to the documentation of this file.00001 #include "web_video_server/ros_compressed_streamer.h"
00002
00003 namespace web_video_server
00004 {
00005
00006 RosCompressedStreamer::RosCompressedStreamer(const async_web_server_cpp::HttpRequest &request,
00007 async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) :
00008 ImageStreamer(request, connection, nh), stream_(connection)
00009 {
00010 stream_.sendInitialHeader();
00011 }
00012
00013 void RosCompressedStreamer::start() {
00014 std::string compressed_topic = topic_ + "/compressed";
00015 image_sub_ = nh_.subscribe(compressed_topic, 1, &RosCompressedStreamer::imageCallback, this);
00016 }
00017
00018 void RosCompressedStreamer::imageCallback(const sensor_msgs::CompressedImageConstPtr &msg) {
00019 try {
00020 std::string content_type;
00021 if(msg->format.find("jpeg") != std::string::npos) {
00022 content_type = "image/jpeg";
00023 }
00024 else if(msg->format.find("png") != std::string::npos) {
00025 content_type = "image/png";
00026 }
00027 else {
00028 ROS_WARN_STREAM("Unknown ROS compressed image format: " << msg->format);
00029 return;
00030 }
00031
00032 stream_.sendPart(msg->header.stamp, content_type, boost::asio::buffer(msg->data), msg);
00033 }
00034 catch (boost::system::system_error &e)
00035 {
00036
00037 ROS_DEBUG("system_error exception: %s", e.what());
00038 inactive_ = true;
00039 return;
00040 }
00041 catch (std::exception &e)
00042 {
00043 ROS_ERROR_THROTTLE(30, "exception: %s", e.what());
00044 inactive_ = true;
00045 return;
00046 }
00047 catch (...)
00048 {
00049 ROS_ERROR_THROTTLE(30, "exception");
00050 inactive_ = true;
00051 return;
00052 }
00053 }
00054
00055
00056 boost::shared_ptr<ImageStreamer> RosCompressedStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request,
00057 async_web_server_cpp::HttpConnectionPtr connection,
00058 ros::NodeHandle& nh)
00059 {
00060 return boost::shared_ptr<ImageStreamer>(new RosCompressedStreamer(request, connection, nh));
00061 }
00062
00063 std::string RosCompressedStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request)
00064 {
00065 std::stringstream ss;
00066 ss << "<img src=\"/stream?";
00067 ss << request.query;
00068 ss << "\"></img>";
00069 return ss.str();
00070 }
00071
00072
00073 }