Go to the documentation of this file.00001
00007
00008
00009
00010
00011 #include <QTextStream>
00012 #include <ros/ros.h>
00013 #include <concert_msgs/Implementation.h>
00014 #include "../include/rocon_qorchestra/implementations.hpp"
00015
00016
00017
00018
00019
00020 namespace rocon_qorchestra {
00021
00022
00023
00024
00025
00026 Implementations::~Implementations() {
00027 for ( unsigned int i = 0; i < external_processes.size(); ++i ) {
00028 if ( external_processes[i]->state() != QProcess::NotRunning ) {
00029 external_processes[i]->kill();
00030 }
00031 delete external_processes[i];
00032 external_processes[i] = NULL;
00033 }
00034 }
00039 bool Implementations::fetch() {
00040 ros::NodeHandle nh;
00041 ros::ServiceClient retreive_implementations_client = nh.serviceClient<concert_msgs::Implementation>("implementation");
00042 if ( retreive_implementations_client.waitForExistence( ros::Duration(5.0)) ) {
00043 concert_msgs::Implementation implementation;
00044 ROS_INFO_STREAM("QOrchestra: requesting implementations.");
00045 if( retreive_implementations_client.call(implementation) ) {
00046 ROS_INFO_STREAM("QOrchestra: service call to load implementation was successful.");
00047 QList<QStandardItem*> implementation_list;
00048 for ( unsigned int i = 0; i < implementation.response.nodes.size(); ++i ) {
00049 implementation_list << new QStandardItem(implementation.response.nodes[i].c_str());
00050 }
00051 mutex_.lock();
00052 dot_graph_ = implementation.response.link_graph.c_str();
00053 model_.clear();
00054 QStandardItem *parent = model_.invisibleRootItem();
00055 QStandardItem *header_item = new QStandardItem(implementation.response.name.c_str());
00056 parent->appendRow(header_item);
00057 header_item->appendColumn(implementation_list);
00058 mutex_.unlock();
00059 Q_EMIT sigImplementationsFetched();
00060 return true;
00061 } else {
00062 ROS_WARN_STREAM("QOrchestra: service call to load implementation was not successful.");
00063 }
00064 } else {
00065 ROS_WARN_STREAM("QOrchestra: implementations server unavailable (is rocon_orchestra running?)");
00066 }
00067 return false;
00068 }
00069
00076 void Implementations::viewLinkGraph()
00077 {
00078 if ( dot_graph_ == "" ) {
00079 ROS_WARN_STREAM("QOrchestra: no implementation loaded yet, aborting view.");
00080 return;
00081 }
00082
00083 if ( dot_graph_file.open() ) {
00084 ROS_INFO_STREAM("QOrchestra: writing dot file [" << dot_graph_file.fileName().toStdString() << "]");
00085 QTextStream out(&dot_graph_file);
00086 out << QString(dot_graph_.c_str());
00087 dot_graph_file.close();
00088 }
00089
00090 QStringList args;
00091 QProcess *dot_graph_viewer = new QProcess();
00092 args << dot_graph_file.fileName();
00093 dot_graph_viewer->start("kgraphviewer",args);
00094 external_processes.push_back(dot_graph_viewer);
00095 }
00096
00097 }
00098