qnode.cpp
Go to the documentation of this file.
00001 
00009 /*****************************************************************************
00010 ** Includes
00011 *****************************************************************************/
00012 
00013 #include <string>
00014 #include <sstream>
00015 
00016 #include <ros/ros.h>
00017 #include <ros/network.h>
00018 #include <std_msgs/String.h>
00019 #include <willow_app_manager/ListApps.h>
00020 #include <willow_app_manager/GetInstallationState.h>
00021 #include <willow_app_manager/GetAppDetails.h>
00022 #include <willow_app_manager/InstallApp.h>
00023 #include <willow_app_manager/UninstallApp.h>
00024 #include <willow_app_manager/StartApp.h>
00025 #include <willow_app_manager/StopApp.h>
00026 
00027 #include "../include/rocon_qorchestra/qnode.hpp"
00028 
00029 /*****************************************************************************
00030 ** Namespaces
00031 *****************************************************************************/
00032 
00033 namespace rocon_qorchestra {
00034 
00035 /*****************************************************************************
00036 ** Implementation
00037 *****************************************************************************/
00038 
00039 QNode::QNode(int argc, char** argv ) :
00040         init_argc_(argc),
00041         init_argv_(argv)
00042 {
00043 //      QStringList concert_clients_model_header;
00044         QStringList model_header;
00045 //      concert_clients_model_header << "Unique Name" << "Suggested Name" << "Device" << "Key" << "Uri" << "Last Connection" << "Status";
00046         model_header << "Unique Name" << "Suggested Name" << "Device" << "Key" << "Uri" << "Last Connection" << "Connected";
00047         concert_clients_model_.setHorizontalHeaderLabels( model_header );
00048 //      model_header.clear();
00049 //      model_header << "App name" << "Installed";
00050 //      QStringList client_apps_model_header;
00051 //      client_apps_model_header << "Unique Name" << "Suggested Name" << "App name" << "Installed";
00052 //  client_apps_model_.setHorizontalHeaderLabels( client_apps_model_header );
00053 //      concert_clients_apps_model_.setHorizontalHeaderLabels( model_header );
00054 }
00055 
00056 QNode::~QNode() {
00057     if( ros::isStarted() ) {
00058       ros::shutdown(); // explicitly needed since we use ros::start();
00059       ros::waitForShutdown();
00060     }
00061         wait();
00062 }
00063 
00064 bool QNode::init()
00065 {
00066         ros::init(init_argc_, init_argv_, "rocon_qorchestra");
00067         if ( ! ros::master::check() ) {
00068                 return false;
00069         }
00070         ros::start(); // explicitly needed since our nodehandle is going out of scope.
00071         establishRosComms();
00072         start();
00073         return true;
00074 }
00075 
00076 bool QNode::init(const std::string &master_url, const std::string &host_url)
00077 {
00078         std::map<std::string,std::string> remappings;
00079         remappings["__master"] = master_url;
00080         remappings["__hostname"] = host_url;
00081         ros::init(remappings,"rocon_qorchestra");
00082         if ( ! ros::master::check() )
00083           return false;
00084         ros::start(); // explicitly needed since our nodehandle is going out of scope.
00085         establishRosComms();
00086         start();
00087         return true;
00088 }
00089 
00090 void QNode::establishRosComms()
00091 {
00092         ros::NodeHandle nh;
00093         concert_clients_subscriber_ = nh.subscribe("concert_clients",10, &QNode::subscribeConcertClients, this);
00094 }
00095 
00096 void QNode::run() {
00097         implementations.fetch();
00098         ros::spin();
00099 //      ros::Rate loop_rate(10);
00100 //      int count = 0;
00101 //      while ( ros::ok() ) {
00102 //
00103 //              std_msgs::String msg;
00104 //              std::stringstream ss;
00105 //              ss << "hello world " << count;
00106 //              msg.data = ss.str();
00107 //              chatter_publisher.publish(msg);
00108 //              log(Info,std::string("I sent: ")+msg.data);
00109 //              ros::spinOnce();
00110 //              loop_rate.sleep();
00111 //              ++count;
00112 //      }
00113         std::cout << "Ros shutdown, proceeding to close the gui." << std::endl;
00114         Q_EMIT rosShutdown(); // used to signal the gui for a shutdown (useful to roslaunch)
00115 }
00116 
00117 
00118 /*****************************************************************************
00119 ** Ros Comms
00120 *****************************************************************************/
00135 void QNode::subscribeConcertClients(const concert_msgs::ConcertClientsConstPtr concert)
00136 {
00137   concert_clients_ptr_ = concert;// store pointer for update
00138         for ( unsigned int i = 0; i < concert->clients.size(); ++i )
00139         {
00140                 ROS_DEBUG_STREAM("Concert Clients: =========== Concert Client List ===========");
00141                 ROS_DEBUG_STREAM("Concert Clients: \t unique name: " << concert->clients[i].unique_name );
00142                 ROS_DEBUG_STREAM("Concert Clients: \t platform: " << concert->clients[i].platform << "."
00143                   << concert->clients[i].system << "." << concert->clients[i].robot);
00144                 ROS_DEBUG_STREAM("Concert Clients: \t suggested_name: " << concert->clients[i].suggested_name );
00145                 ROS_DEBUG_STREAM("Concert Clients: \t key: " << concert->clients[i].key );
00146                 ROS_DEBUG_STREAM("Concert Clients: \t app_manager_uri: " << concert->clients[i].app_manager_uri );
00147                 ROS_DEBUG_STREAM("Concert Clients: \t last_connection_timestamp: "
00148                   << concert->clients[i].last_connection_timestamp );
00149                 if ( concert->clients[i].is_connected )
00150                         ROS_DEBUG_STREAM("Concert Clients: \t is_connected : yes" );
00151                 else
00152                         ROS_DEBUG_STREAM("Concert Clients: \t is_connected : no" );
00153                 ROS_DEBUG_STREAM("Concert Clients: \t zeroconf info: todo" );
00154         }
00155 
00156     // see QGooNode::requestStatus() for an example where it clears, then sets the size explicitly
00157         // blocking signals is useless here, tableview malfunctions withough them.
00158     // bool old_signal_state = concert_clients_model.blockSignals(true);
00159     // concert_clients_model.blockSignals(old_signal_state);
00160         mutex_.lock();
00161         concert_clients_model_.removeRows(0,concert_clients_model_.rowCount());
00162         concert_clients_apps_model_.clear();
00163         for ( unsigned int i = 0; i < concert->clients.size(); ++i )
00164         {
00165                 QList<QStandardItem *> items;
00166                 items << createConcertClientDataElement(concert->clients[i].unique_name);
00167                 items << createConcertClientDataElement(concert->clients[i].suggested_name);
00168                 items << createConcertClientDataElement(concert->clients[i].platform + "." + concert->clients[i].system + "."
00169                     + concert->clients[i].robot);
00170                 items << createConcertClientDataElement(concert->clients[i].key);
00171                 items << createConcertClientDataElement(concert->clients[i].app_manager_uri,Qt::AlignLeft);
00172                 std::stringstream ostream;
00173                 if ( concert->clients[i].is_connected ) {
00174                         ostream << concert->clients[i].last_connection_timestamp;
00175                         items << createConcertClientDataElement(ostream.str());
00176                         items << createConcertClientDataElement("ready boss",Qt::AlignLeft);
00177                 } else {
00178                         items << createConcertClientDataElement("-");
00179                         items << createConcertClientDataElement("-",Qt::AlignLeft);
00180                 }
00181                 concert_clients_model_.appendRow(items);
00182     /*
00183      * Get apps of the client
00184      */
00185     getClientAppsData(concert->clients[i].unique_name);
00186         }
00187     Q_EMIT concertClientsUpdate();
00188         mutex_.unlock();
00189 
00190   /*
00191    * Clear client's apps view
00192    */
00193   mutex_.lock();
00194   client_apps_model_.clear();
00195   QStringList model_header;
00196   model_header << "Installable apps" << "Installed apps";
00197   client_apps_model_.setHorizontalHeaderLabels( model_header );
00198   Q_EMIT clientAppListRetrieved( &client_apps_model_ );
00199   mutex_.unlock();
00200   /*
00201    * Clear app details view
00202    */
00203   mutex_.lock();
00204   app_details_model_.clear();
00205   model_header.clear();
00206   model_header << "";
00207   app_details_model_.setHorizontalHeaderLabels( model_header );
00208   model_header.clear();
00209   model_header << "Name" << "Version" << "Description";
00210   app_details_model_.setVerticalHeaderLabels( model_header );
00211   Q_EMIT appDetailsRetrieved( &app_details_model_ );
00212   mutex_.unlock();
00213 }
00214 
00215 
00220 void QNode::getClientAppsData(std::string robot_namespace)
00221 {
00222 //  std::string robot_namespace = concert->clients[row].unique_name;
00223   ros::NodeHandle nh;
00224   std::stringstream ostream;
00225   ostream << robot_namespace << "'s apps";
00226   QStandardItem* client_apps = new QStandardItem( QString(ostream.str().c_str()) );
00227   /*
00228    * Get client's installable apps
00229    */
00230   QList<QStandardItem*> installable_apps;
00231   ros::ServiceClient list_exchange_apps_client = nh.serviceClient<willow_app_manager::GetInstallationState>(
00232       "/" + robot_namespace + "/list_exchange_apps");
00233   willow_app_manager::GetInstallationState list_installable_apps;
00234   if ( list_exchange_apps_client.waitForExistence( ros::Duration(1.0)) )
00235   {
00236     list_installable_apps.request.remote_update = true;
00237     if (list_exchange_apps_client.call(list_installable_apps))
00238     {
00239       for(unsigned int j = 0; j < list_installable_apps.response.available_apps.size(); ++j)
00240       {
00241         installable_apps << new QStandardItem(list_installable_apps.response.available_apps[j].name.c_str());
00242         ROS_INFO_STREAM("Added app " << list_installable_apps.response.available_apps[j].name << " to the list of "
00243           << robot_namespace << "'s installable apps.");
00244       }
00245     }
00246     else
00247     {
00248       ROS_WARN_STREAM("Service call failed, when trying to receive installable apps list from "
00249           << robot_namespace << ".");
00250       installable_apps << createConcertClientDataElement("No installable apps have been retrieved.");
00251     }
00252   }
00253   else
00254   {
00255     ROS_WARN_STREAM("Service for retrieving " << robot_namespace << "'s installable apps was not advertised in time.");
00256     installable_apps << createConcertClientDataElement("No installable apps have been retrieved.");
00257   }
00258 
00259   /*
00260    * Get client's installed apps
00261    */
00262   ros::ServiceClient list_apps_client = nh.serviceClient<willow_app_manager::ListApps>("/" + robot_namespace +
00263       "/list_apps");
00264   willow_app_manager::ListApps list_installed_apps;
00265   QList<QStandardItem*> installed_apps;
00266   if ( list_apps_client.waitForExistence( ros::Duration(1.0)) )
00267   {
00268     if (list_apps_client.call(list_installed_apps))
00269     {
00270       for(unsigned int j = 0; j < list_installed_apps.response.available_apps.size(); ++j)
00271       {
00272         installed_apps << new QStandardItem(list_installed_apps.response.available_apps[j].name.c_str());
00273         ROS_INFO_STREAM("Added app " << list_installed_apps.response.available_apps[j].name << " to the list of "
00274           << robot_namespace << "'s installed apps.");
00275       }
00276     }
00277     else
00278     {
00279       ROS_WARN_STREAM("Service call failed, when trying to receive installed apps list from " << robot_namespace << ".");
00280       installed_apps << createConcertClientDataElement("No installed apps have been retrieved.");
00281     }
00282   }
00283   else
00284   {
00285     ROS_WARN_STREAM("Service for retrieving " << robot_namespace << "'s apps was not advertised in time.");
00286     installed_apps << createConcertClientDataElement("No installed apps have been retrieved.");
00287   }
00288 //  mutex_.lock();
00289   client_apps->appendColumn(installable_apps);
00290   client_apps->appendColumn(installed_apps);
00291   concert_clients_apps_model_.appendRow(client_apps);
00292 //  mutex_.unlock();
00293 }
00294 
00295 
00296 void QNode::retrieveClientAppList( const QModelIndex &index )
00297 {
00298   current_client_index_ = index;
00299   ROS_INFO_STREAM("Retrieving apps of client '"
00300     << concert_clients_ptr_->clients[current_client_index_.row()].unique_name << "'.");
00301   client_installable_apps_list_ << createConcertClientAppsDataElement("nothing here ...", Qt::AlignLeft);
00302   client_installed_apps_list_ << createConcertClientAppsDataElement("nothing here ...", Qt::AlignLeft);
00303 
00304   if ( index.row() >= 0 && index.row() < concert_clients_apps_model_.rowCount() )
00305   {
00306     int row_count = concert_clients_apps_model_.item(index.row())->rowCount();
00307 //    int column_count = concert_clients_apps_model_.item(row)->columnCount();
00308 //    ROS_INFO_STREAM("Client in row " << row << ": item details: rows =" << row_count
00309 //        << " columns = " << column_count);
00310 
00311     client_installable_apps_list_.clear();
00312     for ( int i = 0; i < row_count; ++i )
00313       if ( concert_clients_apps_model_.item(index.row())->child(i,0) )
00314         client_installable_apps_list_ << createConcertClientAppsDataElement(
00315           concert_clients_apps_model_.item(index.row())->child(i,0)->text().toStdString(), Qt::AlignLeft);
00316 
00317     client_installed_apps_list_.clear();
00318     for ( int i = 0; i < row_count; ++i )
00319       if ( concert_clients_apps_model_.item(index.row())->child(i,1) )
00320         client_installed_apps_list_ << createConcertClientAppsDataElement(
00321           concert_clients_apps_model_.item(index.row())->child(i,1)->text().toStdString(), Qt::AlignLeft);
00322   }
00323   else
00324     ROS_ERROR_STREAM("No client data exists in row number " << index.row() << "! (row count "
00325       << client_apps_model_.rowCount() << ")");
00326 
00327 //  ROS_INFO_STREAM("client_app_list size = " << client_app_list.size());
00328 //  for ( int i = 0; i < client_app_list.size(); ++i )
00329 //    ROS_INFO_STREAM("Client's app list: item " << i << ": " << client_app_list.at(i)->text().toStdString());
00330 //  ROS_INFO_STREAM("client_installed_apps_list size = " << client_installed_apps_list.size());
00331 //  for ( int i = 0; i < client_installed_apps_list.size(); ++i )
00332 //    ROS_INFO_STREAM("Client's installed apps list: item " << i << ": " << client_installed_apps_list.at(i)->text().toStdString());
00333 
00334   mutex_.lock();
00335   client_apps_model_.clear();
00336   client_apps_model_.appendColumn(client_installable_apps_list_);
00337   client_apps_model_.appendColumn(client_installed_apps_list_);
00338   QStringList model_header;
00339   model_header << "Installable apps" << "Installed apps";
00340   client_apps_model_.setHorizontalHeaderLabels( model_header );
00341   mutex_.unlock();
00342 //  ROS_INFO_STREAM("client_apps_model_ size: rows = " << client_apps_model_.rowCount() << ", columns = "
00343 //    << client_apps_model_.columnCount());
00344 
00345   Q_EMIT clientAppListRetrieved(&client_apps_model_);
00346 }
00347 
00348 
00349 void QNode::retrieveAppDetails( const QModelIndex &index )
00350 {
00351   ros::NodeHandle nh;
00352   std::string robot_namespace = concert_clients_ptr_->clients[current_client_index_.row()].unique_name;
00353   ros::ServiceClient app_details_client = nh.serviceClient<willow_app_manager::GetAppDetails>(
00354         "/" + robot_namespace + "/get_app_details");
00355   willow_app_manager::GetAppDetails app_details;
00356   app_details_model_.appendRow(createConcertClientAppsDataElement("nothing here ...", Qt::AlignLeft));
00357   QList<QStandardItem*> app_details_list;
00358   QStringList model_hor_header;
00359   QStringList model_ver_header;
00360   model_hor_header << "";
00361   model_ver_header << "";
00362   if ( index.column() == 0 )
00363     app_details.request.name = client_installable_apps_list_.at(index.row())->text().toStdString();
00364   else
00365     app_details.request.name = client_installed_apps_list_.at(index.row())->text().toStdString();
00366   ROS_INFO_STREAM("Requesting details of app '" << app_details.request.name << "' on '"
00367     << robot_namespace << "'.");
00368   if (app_details_client.call(app_details) )
00369   {
00370     ROS_INFO_STREAM("Service call to get details of app '" << app_details.request.name << "' was successful.");
00371     app_details_list << createConcertClientAppsDataElement(app_details.response.app.display_name, Qt::AlignLeft);
00372 //    app_details_list << new QStandardItem( QIcon(QPixmap(app_details.response.app.icon.data.)),
00373 //      QString(app_details.response.app.display_name.c_str() + "_icon") );
00374     app_details_list << createConcertClientAppsDataElement(app_details.response.app.latest_version, Qt::AlignLeft);
00375     app_details_list << createConcertClientAppsDataElement(app_details.response.app.description, Qt::AlignLeft);
00376     model_hor_header.clear();
00377     model_ver_header.clear();
00378     model_hor_header << QString(app_details.response.app.name.c_str());
00379     model_ver_header << "Name" << "Version" << "Description";
00380   }
00381   else
00382     ROS_WARN_STREAM("Service call to get details of app '" << app_details.request.name << "' was not successful!");
00383 
00384   mutex_.lock();
00385   app_details_model_.clear();
00386   app_details_model_.appendColumn(app_details_list);
00387   app_details_model_.setHorizontalHeaderLabels( model_hor_header );
00388   app_details_model_.setVerticalHeaderLabels( model_ver_header );
00389   mutex_.unlock();
00390   Q_EMIT appDetailsRetrieved(&app_details_model_);
00391 }
00392 
00393 
00394 void QNode::installApp( const QModelIndex &index )
00395 {
00396   ros::NodeHandle nh;
00397   std::string robot_namespace = concert_clients_ptr_->clients[current_client_index_.row()].unique_name;
00398   ros::ServiceClient install_app_client = nh.serviceClient<willow_app_manager::InstallApp>(
00399         "/" + robot_namespace + "/install_app");
00400   willow_app_manager::InstallApp install_app;
00401   install_app.request.name = client_installable_apps_list_.at(index.row())->text().toStdString();
00402   ROS_INFO_STREAM("Requesting installation of app '" << install_app.request.name << "' on '"
00403     << robot_namespace << "'.");
00404   if (install_app_client.call(install_app) )
00405     ROS_INFO_STREAM("Service call to install app '" << install_app.request.name << "' was successful.");
00406   else
00407     ROS_WARN_STREAM("Service call to install app '" << install_app.request.name << "' was not successful!");
00408 
00409   // to refresh the app list; TODO: try to load (only) a fresh app list
00410   subscribeConcertClients(concert_clients_ptr_);
00411 //  retrieveClientAppList(current_client_index_);
00412 }
00413 
00414 
00415 void QNode::uninstallApp( const QModelIndex &index )
00416 {
00417   ros::NodeHandle nh;
00418   std::string robot_namespace = concert_clients_ptr_->clients[current_client_index_.row()].unique_name;
00419   ros::ServiceClient uninstall_app_client = nh.serviceClient<willow_app_manager::UninstallApp>(
00420         "/" + robot_namespace + "/uninstall_app");
00421   willow_app_manager::UninstallApp uninstall_app;
00422   uninstall_app.request.name = client_installed_apps_list_.at(index.row())->text().toStdString();
00423   ROS_INFO_STREAM("Requesting uninstallation of app '" << uninstall_app.request.name << "' on '"
00424       << robot_namespace << "'.");
00425   if (uninstall_app_client.call(uninstall_app) )
00426     ROS_INFO_STREAM("Service call to uninstall app '" << uninstall_app.request.name << "' was successful.");
00427   else
00428     ROS_WARN_STREAM("Service call to uninstall app '" << uninstall_app.request.name << "' was not successful!");
00429 
00430   // to refresh the app list; TODO: try to load (only) a fresh app list
00431   subscribeConcertClients(concert_clients_ptr_);
00432 //  retrieveClientAppList( current_client_index_ );
00433 }
00434 
00440 bool QNode::clientIsConnected(const int &row) {
00441         if ( concert_clients_model_.item(row, 6)->text().toStdString() == "ready boss" ) {
00442                 return true;
00443         } else {
00444                 return false;
00445         }
00446 }
00452 bool QNode::clientIsAndroid(const int &row) {
00453         if ( concert_clients_model_.item(row, 2)->text().toStdString() == "android.ros.xoom" ) {
00454                 return true;
00455         } else {
00456                 return false;
00457         }
00458 }
00464 QString QNode::clientDeviceTriple(const int &row) {
00465         return concert_clients_model_.item(row, 2)->text();
00466 }
00467 
00476 void QNode::checkSolution(const QModelIndex &index) {
00477 
00478         mutex_.lock();
00479         QModelIndex group_index;
00480         QModelIndex parent = implementations.model()->parent(index);
00481         if ( parent.isValid() ) {
00482                 group_index = parent;
00483         } else {
00484                 group_index = index;
00485         }
00486         QStringList requested_devices, requested_device_configurations;
00487         for ( int i = 0; i < implementations.model()->rowCount(group_index); ++i ) {
00488                 QModelIndex child = group_index.child(i,0);
00489                 if ( child.isValid() ) {
00490                         std::string device_configuration(implementations.model()->itemFromIndex(child)->text().toStdString());
00491                         requested_device_configurations << device_configuration.c_str();
00492                         std::string only_device = device_configuration;
00493                         only_device.resize(only_device.find_last_of("."));
00494                         if ( !requested_devices.contains(only_device.c_str()) ) {
00495                                 requested_devices << only_device.c_str();
00496                         }
00497                         ROS_INFO_STREAM("QOrchestra: added device configuration: " << only_device << " [" << device_configuration << "]");
00498                 }
00499         }
00500 
00501         // creating all available device configurations (platform + installed apps)
00502         QStringList available_devices, available_device_configs;
00503         for(int i = 0; i < concert_clients_model_.rowCount(); ++i) {
00504                 // first check, if the concert client is connected at all
00505                 if ( clientIsConnected(i) && !clientIsAndroid(i) ) {
00506                         QString device = clientDeviceTriple(i);
00507                         available_devices << device;
00508                         ROS_DEBUG_STREAM("QOrchestra: Added available device: " << device.toStdString());
00509                         for(int j = 0; j < concert_clients_apps_model_.item(i)->rowCount(); ++j) {
00510                                 if (concert_clients_apps_model_.item(i)->child(j,1) ) {
00511                                         std::stringstream stream;
00512                                         stream << device.toStdString() << "." << concert_clients_apps_model_.item(i)->child(j,1)->text().toStdString();
00513                                         available_device_configs << QString(stream.str().c_str());
00514                                         ROS_DEBUG_STREAM("QOrchestra: Added available device configuration: " << stream.str());
00515                                 }
00516                         }
00517                 } else if ( clientIsConnected(i) && clientIsAndroid(i) ) { // ugly hack
00518                         QString device( concert_clients_model_.item(i, 2)->text() ); // get the detailed client name
00519                         available_devices << device;
00520                         ROS_DEBUG_STREAM("QOrchestra: Added available device: " << device.toStdString());
00521                         std::stringstream stream;
00522                         stream << device.toStdString() << "." << "rocon_voice_commander";
00523                         available_device_configs << QString(stream.str().c_str());
00524                         ROS_DEBUG_STREAM("QOrchestra: Added available device configuration: " << stream.str());
00525                 }
00526         }
00527         mutex_.unlock();
00528 
00529   // checks requested against available devices and device configurations
00530   QStringList missing_devices(requested_devices);
00531   QStringList missing_device_configurations(requested_device_configurations);
00532   for(int i = 0; i < requested_device_configurations.size(); ++i)
00533   {
00534     if ( available_device_configs.contains(requested_device_configurations.at(i)) )
00535     {
00536       missing_device_configurations.removeOne(requested_device_configurations.at(i));
00537       ROS_INFO_STREAM("QOrchestra: Requested device configuration "
00538         << requested_device_configurations.at(i).toStdString() << " is available.");
00539     }
00540   }
00541   for(int i = 0; i < requested_devices.size(); ++i)
00542   {
00543     if ( available_devices.contains(requested_devices.at(i)) )
00544     {
00545       missing_devices.removeOne(requested_devices.at(i));
00546       ROS_INFO_STREAM("QOrchestra: Requested device " << requested_devices.at(i).toStdString() << " is available.");
00547     }
00548   }
00549 
00550   // checks which requirements are met
00551   if ( missing_device_configurations.size() == 0 )
00552   {
00553     ROS_INFO_STREAM("QOrchestra: All device configurations for the selected solution are available.");
00554     ROS_INFO_STREAM("QOrchestra: You can start the solution now.");
00555     solution_device_configurations_ = requested_device_configurations;
00556     Q_EMIT solutionRequirementsMet();
00557   }
00558   else if ( missing_devices.size() == 0 )
00559   {
00560     ROS_INFO_STREAM("QOrchestra: Some device configurations are missing, but all requested devices are available.");
00561     QStandardItem* missing_apps_on_devices = new QStandardItem("missing_apps_on_devices");
00562     for(int i = 0; i < missing_device_configurations.size(); ++i)
00563     {
00564       ROS_INFO_STREAM("QOrchestra: Checking missing device configuration '"
00565         << missing_device_configurations.at(i).toStdString());
00566       QString device_str = missing_device_configurations.at(i);
00567       device_str.resize(device_str.lastIndexOf("."));
00568       QStandardItem* device = new QStandardItem(device_str);
00569       QString app_str = missing_device_configurations.at(i);
00570       app_str.remove(0, app_str.lastIndexOf(".") + 1);
00571       QStandardItem* app = new QStandardItem(app_str);
00572       QList<QStandardItem*> device_and_app_items;
00573       device_and_app_items << device;
00574       device_and_app_items << app;
00575       missing_apps_on_devices->appendRow(device_and_app_items);
00576       ROS_INFO_STREAM("QOrchestra: Solution is missing app '"
00577         << missing_apps_on_devices->child(i, 1)->text().toStdString() << "' on device '"
00578         << missing_apps_on_devices->child(i, 0)->text().toStdString() << "'.");
00579     }
00580 
00581     ROS_INFO_STREAM("QOrchestra: Proceeding with asking for permission to install missing apps.");
00582     Q_EMIT installMissingAppsRequest( missing_apps_on_devices );
00583   }
00584   else
00585   {
00586     ROS_WARN_STREAM("QOrchestra: Not all device have connected to the concert master yet!");
00587     ROS_WARN_STREAM("QOrchestra: Please wait until they connect and check the solution again.");
00588   }
00589 }
00590 
00591 
00592 void QNode::installMissingApps( const QStandardItem* missing_apps_on_devices )
00593 {
00594   ROS_INFO_STREAM("QOrchestra: Installing the missing apps on the corresponding devices.");
00595   ros::NodeHandle nh;
00596   int missing_apps_installed = 0;
00597   for( int i = 0; i < missing_apps_on_devices->rowCount(); ++i )
00598   {
00599     // search connected clients for corresponding platforms and retrieve their name
00600     for( int j = 0; j < concert_clients_model_.rowCount(); ++j )
00601     {
00602       if ( missing_apps_on_devices->child(i, 0)->text().toStdString() ==
00603           concert_clients_model_.item(j, 2)->text().toStdString() )
00604       {
00605         std::string robot_namespace = concert_clients_model_.item(j, 0)->text().toStdString();
00606         ros::ServiceClient install_app_client = nh.serviceClient<willow_app_manager::InstallApp>(
00607           "/" + robot_namespace + "/install_app");
00608         willow_app_manager::InstallApp install_app;
00609         install_app.request.name = missing_apps_on_devices->child(i, 1)->text().toStdString();
00610         ROS_INFO_STREAM("QOrchestra: Requesting installation of app '"
00611             << missing_apps_on_devices->child(i, 1)->text().toStdString() << "' on device '"
00612             << missing_apps_on_devices->child(i, 0)->text().toStdString() << "'.");
00613         if ( install_app_client.call(install_app) )
00614         {
00615           missing_apps_installed++;
00616           j = concert_clients_model_.rowCount();
00617           ROS_INFO_STREAM("QOrchestra: Service call to install app '"
00618             << missing_apps_on_devices->child(i, 1)->text().toStdString() << "' on device '"
00619             << missing_apps_on_devices->child(i, 0)->text().toStdString() << "' was successful.");
00620         }
00621         else
00622           ROS_WARN_STREAM("QOrchestra: Could not install app '"
00623             << missing_apps_on_devices->child(i, 1)->text().toStdString() << "' on device '"
00624             << missing_apps_on_devices->child(i, 0)->text().toStdString() << "'.");
00625       }
00626     }
00627   }
00628   if (missing_apps_installed == missing_apps_on_devices->rowCount() )
00629   {
00630     ROS_INFO_STREAM("QOrchestra: All missing apps have been installed!");
00631     ROS_INFO_STREAM("QOrchestra: Checking the solution again.");
00632     if ( concert_clients_ptr_ )
00633     {
00634         subscribeConcertClients(concert_clients_ptr_);
00635         ros::Duration(2.0).sleep(); // wait some time to let the qorchestra refresh the apps lists of the client
00636         // TODO: improve this!
00637         Q_EMIT missingAppsInstalled(check_solution_index_);
00638     }
00639     else
00640     {
00641       ROS_WARN_STREAM("QOrchestra: Strange, seems like no concert clients have been found yet!");
00642       ROS_WARN_STREAM("QOrchestra: Please manually confirm the solution again in order to ensure, that all necessary"
00643           << "clients are still connected and apps installed.");
00644     }
00645   }
00646   else
00647   {
00648     ROS_WARN_STREAM("QOrchestra: Not all missing apps could be installed!");
00649     ROS_WARN_STREAM("QOrchestra: Please run the confirmation of the selected solution again.");
00650   }
00651 }
00652 
00653 void QNode::triggerSolution(bool start) {
00654     ROS_INFO_STREAM("QOrchestra: Preparing for starting the solution's apps.");
00655     if ( solution_device_configurations_.size() !=  0 ) {
00656         QStandardItem* solution = new QStandardItem("solution");
00657 
00658                 // separate apps from device and search for the clients corresponding to the devices
00659                 for( int i = 0; i < solution_device_configurations_.size(); ++i ) {
00660                         if ( concert_clients_model_.rowCount() != 0 ) {
00661                                 QString device_str = solution_device_configurations_.at(i);
00662                                 device_str.resize(device_str.lastIndexOf("."));
00663                                 QStandardItem* device = new QStandardItem(device_str);
00664                                 QString app_str = solution_device_configurations_.at(i);
00665                                 app_str.remove(0, app_str.lastIndexOf(".") + 1);
00666                                 QStandardItem* app = new QStandardItem(app_str);
00667                                 QStandardItem* client_unique_name = new QStandardItem("empty");
00668                                 QString solution_device = solution_device_configurations_.at(i);
00669                                 solution_device.resize(solution_device_configurations_.at(i).lastIndexOf("."));
00670 
00671                                 for( int j = 0; j < concert_clients_model_.rowCount(); ++j ) {
00672                                         if ( concert_clients_model_.item(j, 2)->text() == solution_device ) {
00673                                                 QString client_unique_name_str = concert_clients_model_.item(j, 0)->text();
00674                                                 client_unique_name = new QStandardItem(client_unique_name_str);
00675                                                 break;
00676                                         }
00677                                 }
00678                                 QList<QStandardItem*> names_devices_apps;
00679                                 names_devices_apps << client_unique_name << device << app;
00680                                 solution->appendRow(names_devices_apps);
00681                         } else {
00682                                 ROS_ERROR_STREAM("QOrchestra: no concert clients connected yet!");
00683                                 return;
00684                         }
00685                 }
00686 
00687                 // trigger the service calls to start the apps
00688                 ros::NodeHandle nh;
00689                 int apps_triggered = 0;
00690                 for( int i = 0; i < solution->rowCount(); ++i ) {
00691 //      if ( missing_apps_on_devices->child(i, 0)->text().toStdString() ==
00692 //                concert_clients_model_.item(j, 2)->text().toStdString() )
00693             {
00694                 std::string robot_namespace = solution->child(i, 0)->text().toStdString();
00695                 std::string app_name = solution->child(i, 2)->text().toStdString();
00696                 std::string trigger_string;
00697                 if ( start ) {
00698                         ros::ServiceClient app_client = nh.serviceClient<willow_app_manager::StartApp>("/" + robot_namespace + "/start_app");
00699                         willow_app_manager::StartApp start_app;
00700                         start_app.request.name = app_name;
00701                         if ( app_client.call(start_app) ) {
00702                                 apps_triggered++;
00703                                 ROS_INFO_STREAM("QOrchestra: service call to start app was successful [" << app_name << "][" << robot_namespace << "]");
00704                         } else {
00705                                 ROS_WARN_STREAM("QOrchestra: service call to start app failed [" << app_name << "][" << robot_namespace << "]");
00706                         }
00707                 } else {
00708                         ros::ServiceClient app_client = nh.serviceClient<willow_app_manager::StopApp>("/" + robot_namespace + "/stop_app");
00709                         willow_app_manager::StopApp stop_app;
00710                         stop_app.request.name = app_name;
00711                         if ( app_client.call(stop_app) ) {
00712                                 apps_triggered++;
00713                                 ROS_INFO_STREAM("QOrchestra: service call to stop app was successful [" << app_name << "][" << robot_namespace << "]");
00714                         } else {
00715                                 ROS_WARN_STREAM("QOrchestra: service call to stop app failed [" << app_name << "][" << robot_namespace << "]");
00716                         }
00717                 }
00718             }
00719                 }
00720                 if ( apps_triggered == solution->rowCount() ) {
00721                 if ( start ) {
00722                         ROS_INFO_STREAM("QOrchestra: all apps started.");
00723                 } else {
00724                         ROS_INFO_STREAM("QOrchestra: all apps stopped.");
00725                 }
00726                 } else {
00727                 if ( start ) {
00728                         ROS_ERROR_STREAM("QOrchestra: not all apps started.");
00729                 } else {
00730                         ROS_ERROR_STREAM("QOrchestra: not all apps stopped.");
00731                 }
00732                 }
00733     } else {
00734         ROS_ERROR_STREAM("QOrchestra: solution contains no apps to start!");
00735     }
00736 }
00737 
00738 
00739 /*****************************************************************************
00740 ** Utilities
00741 *****************************************************************************/
00742 
00743 QStandardItem* QNode::createConcertClientDataElement(const std::string &str, const Qt::Alignment &alignment)
00744 {
00745         QStandardItem *item = new QStandardItem( QString(str.c_str()) );
00746         item->setTextAlignment(alignment);
00747         item->setEditable(false); // some of these will be editable later (to send commands).
00748         return item;
00749 }
00750 
00751 
00752 QStandardItem* QNode::createConcertClientAppsDataElement(const std::string &str, const Qt::Alignment &alignment)
00753 {
00754   QStandardItem *item = new QStandardItem( QString(str.c_str()) );
00755   item->setTextAlignment(alignment);
00756   item->setEditable(false); // some of these will be editable later (to send commands).
00757   //item->setEnabled(false); // some of these will be editable later (to send commands).
00758   return item;
00759 }
00760 
00761 }  // namespace rocon_qorchestra
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


graveyard_rocon_qorchestra
Author(s): Daniel Stonier
autogenerated on Wed Jan 23 2013 13:42:01