app_loader.cpp
Go to the documentation of this file.
00001 
00023 #include "app_loader/app_loader.h"
00024 
00025 namespace app_loader{
00026 
00027     AppLoader::AppLoader()
00028     {
00029         ros::NodeHandle private_nh("~");
00030         ros::NodeHandle nh;
00031 
00032         rtp_manager_destroy_ = false;
00033 
00034         //get app name and type
00035         private_nh.param("app_name", app_name_, std::string("app_demo"));
00036         private_nh.param("app_type", app_type_, std::string("micros_swarm/AppDemo"));
00037 
00038         ros::ServiceClient client = nh.serviceClient<app_loader::AppLoad>("app_loader_load_app");
00039         app_loader::AppLoad srv;
00040         srv.request.name = app_name_;
00041         srv.request.type = app_type_;
00042         if (client.call(srv))
00043         {
00044             ROS_INFO("[AppLoader]: App %s loaded successfully.", app_name_.c_str());
00045         }
00046         else
00047         {
00048             ROS_ERROR("[AppLoader]: Failed to load App %s.", app_name_.c_str());
00049         }
00050 
00051         //when the rtp manager was destroyed, automatically unload the apps
00052         std::string topic_name = "runtime_core_destroy_" + app_name_;
00053         rtp_manager_destroy_srv_ = nh.advertiseService(topic_name, &AppLoader::rtpManagerDestroyCB, this);
00054     }
00055 
00056     AppLoader::~AppLoader()
00057     {
00058         rtp_manager_destroy_srv_.shutdown();
00059         if(!rtp_manager_destroy_) {
00060             ros::NodeHandle nh;
00061             ros::ServiceClient client = nh.serviceClient<app_loader::AppUnload>("app_loader_unload_app");
00062             app_loader::AppUnload srv;
00063             srv.request.name = app_name_;
00064             srv.request.type = app_type_;
00065 
00066             if (client.call(srv)) {
00067                 ROS_INFO("[AppLoader]: App %s was unloaded successfully.", app_name_.c_str());
00068             } else {
00069                 ROS_ERROR("[AppLoader]: Failed to unload App %s.", app_name_.c_str());
00070             }
00071         }
00072         else{
00073             ROS_INFO("RTPManager was destroyed before the AppLoader.");
00074         }
00075     }
00076 
00077     bool AppLoader::rtpManagerDestroyCB(app_loader::RTDestroy::Request &req, app_loader::RTDestroy::Response &resp)
00078     {
00079         resp.success = false;
00080         if(req.code == 1) {
00081             rtp_manager_destroy_ = true;
00082             resp.success = true;
00083         }
00084 
00085         ros::shutdown();
00086         return true;
00087     }
00088 
00089     bool AppLoader::ok()
00090     {
00091         return !rtp_manager_destroy_;
00092     }
00093 };
00094 
00095 


app_loader
Author(s):
autogenerated on Thu Jun 6 2019 18:52:08