in rosbag_cloud_recorders/src/utils/recorder.cpp [597:652]
void Recorder::DoCheckMaster(ros::TimerEvent const& e, ros::NodeHandle& node_handle) {
(void) e;
ros::master::V_TopicInfo topics;
if (ros::master::getTopics(topics)) {
for (ros::master::TopicInfo const& t : topics) {
if (ShouldSubscribeToTopic(t.name)) {
shared_ptr<ros::Subscriber> sub = Subscribe(node_handle, t.name);
currently_recording_.insert(t.name);
subscribers_.push_back(sub);
}
}
}
if (options_.node != std::string(""))
{
XmlRpc::XmlRpcValue req;
req[0] = ros::this_node::getName();
req[1] = options_.node;
XmlRpc::XmlRpcValue resp;
XmlRpc::XmlRpcValue payload;
if (ros::master::execute("lookupNode", req, resp, payload, true))
{
std::string peer_host;
uint32_t peer_port;
if (!ros::network::splitURI(static_cast<std::string>(resp[2]), peer_host, peer_port))
{
ROS_ERROR("Bad xml-rpc URI trying to inspect node at: [%s]", static_cast<std::string>(resp[2]).c_str());
} else {
XmlRpc::XmlRpcClient c(peer_host.c_str(), peer_port, "/");
XmlRpc::XmlRpcValue req2;
XmlRpc::XmlRpcValue resp2;
req2[0] = ros::this_node::getName();
c.execute("getSubscriptions", req2, resp2);
if (!c.isFault() && resp2.valid() && resp2.size() > 0 && static_cast<int>(resp2[0]) == 1)
{
for(int i = 0; i < resp2[2].size(); i++)
{
if (ShouldSubscribeToTopic(resp2[2][i][0], true))
{
shared_ptr<ros::Subscriber> sub = Subscribe(node_handle, resp2[2][i][0]);
currently_recording_.insert(resp2[2][i][0]);
subscribers_.push_back(sub);
}
}
} else {
ROS_ERROR("Node at: [%s] failed to return subscriptions.", static_cast<std::string>(resp[2]).c_str());
}
}
}
}
}