Skip to content

Instantly share code, notes, and snippets.

@martonmiklos
Created April 18, 2016 20:35
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save martonmiklos/44f59cc921858771b4b6dc061e8e29e2 to your computer and use it in GitHub Desktop.
Save martonmiklos/44f59cc921858771b4b6dc061e8e29e2 to your computer and use it in GitHub Desktop.
#include <ros/ros.h>
#include <ros/publisher.h>
#include <ros/master.h>
int main(int argc, char** argv)
{
ros::init(argc, argv, "ros_something");
ros::start();
XmlRpc::XmlRpcValue params("ros_topic_list");
XmlRpc::XmlRpcValue results;
XmlRpc::XmlRpcValue r;
if(ros::master::execute("getTopicTypes", params, results, r, false) == true)
{
if(results.getType() == XmlRpc::XmlRpcValue::TypeArray)
{
int32_t i = 2;
if(results[i].getType() == XmlRpc::XmlRpcValue::TypeArray)
{
for (int32_t j = 0; j < results[i].size(); ++j)
{
if(results[i][j].getType() == XmlRpc::XmlRpcValue::TypeArray)
{
if(results[i][j].size() == 2)
{
if(results[i][j][0].getType() == XmlRpc::XmlRpcValue::TypeString
&& results[i][j][1].getType() == XmlRpc::XmlRpcValue::TypeString)
{
std::string topic = static_cast<std::string>(results[i][j][0]);
std::string type = static_cast<std::string>(results[i][j][1]);
std::cout<<"Topic : "<<topic<<" -> "<<type<<std::endl;
}
}
}
}
}
}
}
ros::master::V_TopicInfo master_topics;
ros::master::getTopics(master_topics);
for (ros::master::V_TopicInfo::iterator it = master_topics.begin() ; it != master_topics.end(); it++) {
const ros::master::TopicInfo& info = *it;
std::cout << "Topic : " << it - master_topics.begin() << ": " << info.name << " -> " << info.datatype << std::endl;
}
ros::shutdown();
return 0;
}
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment