@@ -74,6 +74,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh)
74
74
stream_types_[" vp9" ] = boost::shared_ptr<ImageStreamerType>(new Vp9StreamerType ());
75
75
76
76
handler_group_.addHandlerForPath (" /" , boost::bind (&WebVideoServer::handle_list_streams, this , _1, _2, _3, _4));
77
+ handler_group_.addHandlerForPath (" /json" , boost::bind (&WebVideoServer::handle_list_streams_json, this , _1, _2, _3, _4));
77
78
handler_group_.addHandlerForPath (" /stream" , boost::bind (&WebVideoServer::handle_stream, this , _1, _2, _3, _4));
78
79
handler_group_.addHandlerForPath (" /stream_viewer" ,
79
80
boost::bind (&WebVideoServer::handle_stream_viewer, this , _1, _2, _3, _4));
@@ -342,8 +343,72 @@ bool WebVideoServer::handle_list_streams(const async_web_server_cpp::HttpRequest
342
343
return true ;
343
344
}
344
345
345
- }
346
+ bool WebVideoServer::handle_list_streams_json (const async_web_server_cpp::HttpRequest &request,
347
+ async_web_server_cpp::HttpConnectionPtr connection, const char * begin,
348
+ const char * end)
349
+ {
350
+ std::string image_message_type = ros::message_traits::datatype<sensor_msgs::Image>();
351
+ std::string camera_info_message_type = ros::message_traits::datatype<sensor_msgs::CameraInfo>();
352
+
353
+ ros::master::V_TopicInfo topics;
354
+ ros::master::getTopics (topics);
355
+ ros::master::V_TopicInfo::iterator it;
356
+ std::vector<std::string> image_topics;
357
+ std::vector<std::string> camera_info_topics;
358
+ for (it = topics.begin (); it != topics.end (); ++it)
359
+ {
360
+ const ros::master::TopicInfo &topic = *it;
361
+ if (topic.datatype == image_message_type)
362
+ {
363
+ image_topics.push_back (topic.name );
364
+ }
365
+ else if (topic.datatype == camera_info_message_type)
366
+ {
367
+ camera_info_topics.push_back (topic.name );
368
+ }
369
+ }
346
370
371
+ async_web_server_cpp::HttpReply::builder (async_web_server_cpp::HttpReply::ok).header (" Connection" , " close" ).header (
372
+ " Server" , " web_video_server" ).header (" Cache-Control" ,
373
+ " no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0" ).
374
+ header (" Pragma" , " no-cache" ).
375
+ header (" Content-type" , " application/json;" ).
376
+ header (" Access-Control-Allow-Headers" , " *" ).
377
+ header (" Keep-Alive" , " timeout=1" ).
378
+ header (" Access-Control-Allow-Origin" , " *" ).write (connection);
379
+
380
+ connection->write (" [" );
381
+ bool first = true ;
382
+ BOOST_FOREACH (std::string & camera_info_topic, camera_info_topics)
383
+ {
384
+ if (boost::algorithm::ends_with (camera_info_topic, " /camera_info" ))
385
+ {
386
+ std::string base_topic = camera_info_topic.substr (0 , camera_info_topic.size () - strlen (" camera_info" ));
387
+ std::vector<std::string>::iterator image_topic_itr = image_topics.begin ();
388
+ for (; image_topic_itr != image_topics.end ();)
389
+ {
390
+ if (boost::starts_with (*image_topic_itr, base_topic))
391
+ {
392
+ if (!first)
393
+ connection->write (" ," );
394
+ first = false ;
395
+ connection->write (" \" " );
396
+ connection->write (*image_topic_itr);
397
+ connection->write (" \" " );
398
+
399
+ image_topic_itr = image_topics.erase (image_topic_itr);
400
+ }
401
+ else
402
+ {
403
+ ++image_topic_itr;
404
+ }
405
+ }
406
+ }
407
+ }
408
+ connection->write (" ]" );
409
+ return true ;
410
+ }
411
+ }
347
412
int main (int argc, char **argv)
348
413
{
349
414
ros::init (argc, argv, " web_video_server" );
0 commit comments