1 #include <boost/foreach.hpp>
2 #include <boost/lexical_cast.hpp>
3 #include <boost/algorithm/string/predicate.hpp>
6 #include <opencv2/opencv.hpp>
35 forward(request, connection, begin, end);
38 catch (std::exception &e)
47 nh_(nh), handler_group_(
50 #if ROS_HAS_STEADYTIMER || defined USE_STEADY_TIMER
59 private_nh.
param<std::string>(
"address",
address_,
"0.0.0.0");
62 private_nh.
param(
"server_threads", server_threads, 1);
89 catch(boost::exception& e)
126 typedef std::vector<boost::shared_ptr<ImageStreamer> >::iterator itr_type;
130 (*itr)->restreamFrame( max_age );
139 typedef std::vector<boost::shared_ptr<ImageStreamer> >::iterator itr_type;
162 if (type == std::string(
"ros_compressed"))
164 std::string compressed_topic_name = topic +
"/compressed";
167 bool did_find_compressed_topic =
false;
168 for(ros::master::V_TopicInfo::iterator it = topics.begin(); it != topics.end(); ++it)
170 if (it->name == compressed_topic_name)
172 did_find_compressed_topic =
true;
176 if (!did_find_compressed_topic)
178 ROS_WARN_STREAM(
"Could not find compressed image topic for " << topic <<
", falling back to mjpeg");
216 if (type == std::string(
"ros_compressed"))
219 std::string compressed_topic_name = topic +
"/compressed";
222 bool did_find_compressed_topic =
false;
223 for(ros::master::V_TopicInfo::iterator it = topics.begin(); it != topics.end(); ++it)
225 if (it->name == compressed_topic_name)
227 did_find_compressed_topic =
true;
231 if (!did_find_compressed_topic)
233 ROS_WARN_STREAM(
"Could not find compressed image topic for " << topic <<
", falling back to mjpeg");
239 "Server",
"web_video_server").
header(
"Content-type",
"text/html;").
write(connection);
241 std::stringstream ss;
242 ss <<
"<html><head><title>" << topic <<
"</title></head><body>";
243 ss <<
"<h1>" << topic <<
"</h1>";
245 ss <<
"</body></html>";
246 connection->write(ss.str());
260 std::string image_message_type = ros::message_traits::datatype<sensor_msgs::Image>();
261 std::string camera_info_message_type = ros::message_traits::datatype<sensor_msgs::CameraInfo>();
265 ros::master::V_TopicInfo::iterator it;
266 std::vector<std::string> image_topics;
267 std::vector<std::string> camera_info_topics;
268 for (it = topics.begin(); it != topics.end(); ++it)
271 if (topic.
datatype == image_message_type)
273 image_topics.push_back(topic.
name);
275 else if (topic.
datatype == camera_info_message_type)
277 camera_info_topics.push_back(topic.
name);
282 "Server",
"web_video_server").
header(
"Cache-Control",
283 "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").
header(
284 "Pragma",
"no-cache").
header(
"Content-type",
"text/html;").
write(connection);
286 connection->write(
"<html>"
287 "<head><title>ROS Image Topic List</title></head>"
288 "<body><h1>Available ROS Image Topics:</h1>");
289 connection->write(
"<ul>");
290 BOOST_FOREACH(std::string & camera_info_topic, camera_info_topics)
292 if (boost::algorithm::ends_with(camera_info_topic,
"/camera_info"))
294 std::string base_topic = camera_info_topic.substr(0, camera_info_topic.size() - strlen(
"camera_info"));
295 connection->write(
"<li>");
296 connection->write(base_topic);
297 connection->write(
"<ul>");
298 std::vector<std::string>::iterator image_topic_itr = image_topics.begin();
299 for (; image_topic_itr != image_topics.end();)
301 if (boost::starts_with(*image_topic_itr, base_topic))
303 connection->write(
"<li><a href=\"/stream_viewer?topic=");
304 connection->write(*image_topic_itr);
305 connection->write(
"\">");
306 connection->write(image_topic_itr->substr(base_topic.size()));
307 connection->write(
"</a> (");
308 connection->write(
"<a href=\"/snapshot?topic=");
309 connection->write(*image_topic_itr);
310 connection->write(
"\">Snapshot</a>)");
311 connection->write(
"</li>");
313 image_topic_itr = image_topics.erase(image_topic_itr);
320 connection->write(
"</ul>");
322 connection->write(
"</li>");
324 connection->write(
"</ul>");
326 connection->write(
"<ul>");
327 std::vector<std::string>::iterator image_topic_itr = image_topics.begin();
328 for (; image_topic_itr != image_topics.end();) {
329 connection->write(
"<li><a href=\"/stream_viewer?topic=");
330 connection->write(*image_topic_itr);
331 connection->write(
"\">");
332 connection->write(*image_topic_itr);
333 connection->write(
"</a> (");
334 connection->write(
"<a href=\"/snapshot?topic=");
335 connection->write(*image_topic_itr);
336 connection->write(
"\">Snapshot</a>)");
337 connection->write(
"</li>");
339 image_topic_itr = image_topics.erase(image_topic_itr);
341 connection->write(
"</ul></body></html>");
347 int main(
int argc,
char **argv)
349 ros::init(argc, argv,
"web_video_server");