2 #include "async_web_server_cpp/http_reply.hpp" 8 async_web_server_cpp::HttpConnectionPtr connection,
ros::NodeHandle& nh) :
11 quality_ = request.get_query_param_value_or_default<
int>(
"quality", 95);
23 std::vector<int> encode_params;
24 encode_params.push_back(CV_IMWRITE_JPEG_QUALITY);
27 std::vector<uchar> encoded_buffer;
28 cv::imencode(
".jpeg", img, encoded_buffer, encode_params);
34 async_web_server_cpp::HttpConnectionPtr connection,
43 ss <<
"<img src=\"/stream?";
50 async_web_server_cpp::HttpConnectionPtr connection,
54 quality_ = request.get_query_param_value_or_default<
int>(
"quality", 95);
65 std::vector<int> encode_params;
66 encode_params.push_back(CV_IMWRITE_JPEG_QUALITY);
69 std::vector<uchar> encoded_buffer;
70 cv::imencode(
".jpeg", img, encoded_buffer, encode_params);
73 sprintf(stamp,
"%.06lf", time.
toSec());
74 async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok)
75 .header(
"Connection",
"close")
76 .header(
"Server",
"web_video_server")
77 .header(
"Cache-Control",
78 "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, " 80 .header(
"X-Timestamp", stamp)
81 .header(
"Pragma",
"no-cache")
82 .header(
"Content-type",
"image/jpeg")
83 .header(
"Access-Control-Allow-Origin",
"*")
84 .header(
"Content-Length",
85 boost::lexical_cast<std::string>(encoded_buffer.size()))
virtual void sendImage(const cv::Mat &, const ros::Time &time)
async_web_server_cpp::HttpConnectionPtr connection_
void sendPartAndClear(const ros::Time &time, const std::string &type, std::vector< unsigned char > &data)
boost::shared_ptr< ImageStreamer > create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
JpegSnapshotStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
virtual void sendImage(const cv::Mat &, const ros::Time &time)
MjpegStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
std::string create_viewer(const async_web_server_cpp::HttpRequest &request)