Skip to content

Commit 5eab98c

Browse files
committed
Add JSON endpoint
1 parent ad7b42c commit 5eab98c

File tree

2 files changed

+69
-1
lines changed

2 files changed

+69
-1
lines changed

include/web_video_server/web_video_server.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,9 @@ class WebVideoServer
4949
bool handle_list_streams(const async_web_server_cpp::HttpRequest &request,
5050
async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
5151

52+
bool handle_list_streams_json(const async_web_server_cpp::HttpRequest &request,
53+
async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
54+
5255
private:
5356
void restreamFrames(double max_age);
5457
void cleanup_inactive_streams();

src/web_video_server.cpp

Lines changed: 66 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,6 +74,7 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh)
7474
stream_types_["vp9"] = boost::shared_ptr<ImageStreamerType>(new Vp9StreamerType());
7575

7676
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));
7778
handler_group_.addHandlerForPath("/stream", boost::bind(&WebVideoServer::handle_stream, this, _1, _2, _3, _4));
7879
handler_group_.addHandlerForPath("/stream_viewer",
7980
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
342343
return true;
343344
}
344345

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+
}
346370

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+
}
347412
int main(int argc, char **argv)
348413
{
349414
ros::init(argc, argv, "web_video_server");

0 commit comments

Comments
 (0)