controller_manager.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2012, hiDOF, INC and Willow Garage, Inc
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the names of Willow Garage, Inc., hiDOF Inc, nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 /*
00028  * Author: Wim Meeussen
00029  */
00030 
00031 #include "controller_manager/controller_manager.h"
00032 #include <algorithm>
00033 #include <boost/thread/thread.hpp>
00034 #include <boost/thread/condition.hpp>
00035 #include <sstream>
00036 #include <ros/console.h>
00037 #include <controller_manager/controller_loader.h>
00038 #include <controller_manager_msgs/ControllerState.h>
00039 
00040 namespace controller_manager{
00041 
00042 
00043 ControllerManager::ControllerManager(hardware_interface::RobotHW *robot_hw, const ros::NodeHandle& nh) :
00044   robot_hw_(robot_hw),
00045   root_nh_(nh),
00046   cm_node_(nh, "controller_manager"),
00047   start_request_(0),
00048   stop_request_(0),
00049   please_switch_(false),
00050   current_controllers_list_(0),
00051   used_by_realtime_(-1)
00052 {
00053   // create controller loader
00054   controller_loaders_.push_back( LoaderPtr(new ControllerLoader<controller_interface::ControllerBase>("controller_interface",
00055                                                                                                       "controller_interface::ControllerBase") ) );
00056 
00057   // Advertise services (this should be the last thing we do in init)
00058   srv_list_controllers_ = cm_node_.advertiseService("list_controllers", &ControllerManager::listControllersSrv, this);
00059   srv_list_controller_types_ = cm_node_.advertiseService("list_controller_types", &ControllerManager::listControllerTypesSrv, this);
00060   srv_load_controller_ = cm_node_.advertiseService("load_controller", &ControllerManager::loadControllerSrv, this);
00061   srv_unload_controller_ = cm_node_.advertiseService("unload_controller", &ControllerManager::unloadControllerSrv, this);
00062   srv_switch_controller_ = cm_node_.advertiseService("switch_controller", &ControllerManager::switchControllerSrv, this);
00063   srv_reload_libraries_ = cm_node_.advertiseService("reload_controller_libraries", &ControllerManager::reloadControllerLibrariesSrv, this);
00064 }
00065 
00066 
00067 ControllerManager::~ControllerManager()
00068 {}
00069 
00070 
00071 
00072 
00073 // Must be realtime safe.
00074 void ControllerManager::update(const ros::Time& time, const ros::Duration& period, bool reset_controllers)
00075 {
00076   used_by_realtime_ = current_controllers_list_;
00077   std::vector<ControllerSpec> &controllers = controllers_lists_[used_by_realtime_];
00078 
00079   // Restart all running controllers if motors are re-enabled
00080   if (reset_controllers){
00081     for (size_t i=0; i<controllers.size(); i++){
00082       if (controllers[i].c->isRunning()){
00083         controllers[i].c->stopRequest(time);
00084         controllers[i].c->startRequest(time);
00085       }
00086     }
00087   }
00088 
00089 
00090   // Update all controllers
00091   for (size_t i=0; i<controllers.size(); i++)
00092     controllers[i].c->updateRequest(time, period);
00093 
00094   // there are controllers to start/stop
00095   if (please_switch_)
00096   {
00097     // switch hardware interfaces (if any)
00098     robot_hw_->doSwitch(switch_start_list_, switch_stop_list_);
00099 
00100     // stop controllers
00101     for (unsigned int i=0; i<stop_request_.size(); i++)
00102       if (!stop_request_[i]->stopRequest(time))
00103         ROS_FATAL("Failed to stop controller in realtime loop. This should never happen.");
00104 
00105     // start controllers
00106     for (unsigned int i=0; i<start_request_.size(); i++)
00107       if (!start_request_[i]->startRequest(time))
00108         ROS_FATAL("Failed to start controller in realtime loop. This should never happen.");
00109 
00110     please_switch_ = false;
00111   }
00112 }
00113 
00114 controller_interface::ControllerBase* ControllerManager::getControllerByName(const std::string& name)
00115 {
00116   // Lock recursive mutex in this context
00117   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00118 
00119   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00120   for (size_t i = 0; i < controllers.size(); ++i)
00121   {
00122     if (controllers[i].info.name == name)
00123       return controllers[i].c.get();
00124   }
00125   return NULL;
00126 }
00127 
00128 void ControllerManager::getControllerNames(std::vector<std::string> &names)
00129 {
00130   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00131   names.clear();
00132   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00133   for (size_t i = 0; i < controllers.size(); ++i)
00134   {
00135     names.push_back(controllers[i].info.name);
00136   }
00137 }
00138 
00139 
00140 bool ControllerManager::loadController(const std::string& name)
00141 {
00142   ROS_DEBUG("Will load controller '%s'", name.c_str());
00143 
00144   // lock controllers
00145   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00146 
00147   // get reference to controller list
00148   int free_controllers_list = (current_controllers_list_ + 1) % 2;
00149   while (ros::ok() && free_controllers_list == used_by_realtime_){
00150     if (!ros::ok())
00151       return false;
00152     usleep(200);
00153   }
00154   std::vector<ControllerSpec>
00155     &from = controllers_lists_[current_controllers_list_],
00156     &to = controllers_lists_[free_controllers_list];
00157   to.clear();
00158 
00159   // Copy all controllers from the 'from' list to the 'to' list
00160   for (size_t i = 0; i < from.size(); ++i)
00161     to.push_back(from[i]);
00162 
00163   // Checks that we're not duplicating controllers
00164   for (size_t j = 0; j < to.size(); ++j)
00165   {
00166     if (to[j].info.name == name)
00167     {
00168       to.clear();
00169       ROS_ERROR("A controller named '%s' was already loaded inside the controller manager", name.c_str());
00170       return false;
00171     }
00172   }
00173 
00174   ros::NodeHandle c_nh;
00175   // Constructs the controller
00176   try{
00177     c_nh = ros::NodeHandle(root_nh_, name);
00178   }
00179   catch(std::exception &e) {
00180     ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s':\n%s", name.c_str(), e.what());
00181     return false;
00182   }
00183   catch(...){
00184     ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s'", name.c_str());
00185     return false;
00186   }
00187   boost::shared_ptr<controller_interface::ControllerBase> c;
00188   std::string type;
00189   if (c_nh.getParam("type", type))
00190   {
00191     ROS_DEBUG("Constructing controller '%s' of type '%s'", name.c_str(), type.c_str());
00192     try
00193     {
00194       // Trying loading the controller using all of our controller loaders. Exit once we've found the first valid loaded controller
00195       std::list<LoaderPtr>::iterator it = controller_loaders_.begin();
00196       while (!c && it != controller_loaders_.end())
00197       {
00198         std::vector<std::string> cur_types = (*it)->getDeclaredClasses();
00199         for(size_t i=0; i < cur_types.size(); i++){
00200           if (type == cur_types[i]){
00201             c = (*it)->createInstance(type);
00202           }
00203         }
00204         ++it;
00205       }
00206     }
00207     catch (const std::runtime_error &ex)
00208     {
00209       ROS_ERROR("Could not load class %s: %s", type.c_str(), ex.what());
00210     }
00211   }
00212   else
00213   {
00214     ROS_ERROR("Could not load controller '%s' because the type was not specified. Did you load the controller configuration on the parameter server (namespace: '%s')?", name.c_str(), c_nh.getNamespace().c_str());
00215     to.clear();
00216     return false;
00217   }
00218 
00219   // checks if controller was constructed
00220   if (!c)
00221   {
00222     ROS_ERROR("Could not load controller '%s' because controller type '%s' does not exist.",  name.c_str(), type.c_str());
00223     ROS_ERROR("Use 'rosservice call controller_manager/list_controller_types' to get the available types");
00224     to.clear();
00225     return false;
00226   }
00227 
00228   // Initializes the controller
00229   ROS_DEBUG("Initializing controller '%s'", name.c_str());
00230   bool initialized;
00231   controller_interface::ControllerBase::ClaimedResources claimed_resources; // Gets populated during initRequest call
00232   try{
00233     initialized = c->initRequest(robot_hw_, root_nh_, c_nh, claimed_resources);
00234   }
00235   catch(std::exception &e){
00236     ROS_ERROR("Exception thrown while initializing controller %s.\n%s", name.c_str(), e.what());
00237     initialized = false;
00238   }
00239   catch(...){
00240     ROS_ERROR("Exception thrown while initializing controller %s", name.c_str());
00241     initialized = false;
00242   }
00243   if (!initialized)
00244   {
00245     to.clear();
00246     ROS_ERROR("Initializing controller '%s' failed", name.c_str());
00247     return false;
00248   }
00249   ROS_DEBUG("Initialized controller '%s' successful", name.c_str());
00250 
00251   // Adds the controller to the new list
00252   to.resize(to.size() + 1);
00253   to[to.size()-1].info.type = type;
00254   to[to.size()-1].info.name = name;
00255   to[to.size()-1].info.claimed_resources = claimed_resources;
00256   to[to.size()-1].c = c;
00257 
00258   // Destroys the old controllers list when the realtime thread is finished with it.
00259   int former_current_controllers_list_ = current_controllers_list_;
00260   current_controllers_list_ = free_controllers_list;
00261   while (ros::ok() && used_by_realtime_ == former_current_controllers_list_){
00262     if (!ros::ok())
00263       return false;
00264     usleep(200);
00265   }
00266   from.clear();
00267 
00268   ROS_DEBUG("Successfully load controller '%s'", name.c_str());
00269   return true;
00270 }
00271 
00272 
00273 
00274 
00275 bool ControllerManager::unloadController(const std::string &name)
00276 {
00277   ROS_DEBUG("Will unload controller '%s'", name.c_str());
00278 
00279   // lock the controllers
00280   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00281 
00282   // get reference to controller list
00283   int free_controllers_list = (current_controllers_list_ + 1) % 2;
00284   while (ros::ok() && free_controllers_list == used_by_realtime_){
00285     if (!ros::ok())
00286       return false;
00287     usleep(200);
00288   }
00289   std::vector<ControllerSpec>
00290     &from = controllers_lists_[current_controllers_list_],
00291     &to = controllers_lists_[free_controllers_list];
00292   to.clear();
00293 
00294   // Transfers the running controllers over, skipping the one to be removed and the running ones.
00295   bool removed = false;
00296   for (size_t i = 0; i < from.size(); ++i)
00297   {
00298     if (from[i].info.name == name){
00299       if (from[i].c->isRunning()){
00300         to.clear();
00301         ROS_ERROR("Could not unload controller with name %s because it is still running",
00302                   name.c_str());
00303         return false;
00304       }
00305       removed = true;
00306     }
00307     else
00308       to.push_back(from[i]);
00309   }
00310 
00311   // Fails if we could not remove the controllers
00312   if (!removed)
00313   {
00314     to.clear();
00315     ROS_ERROR("Could not unload controller with name %s because no controller with this name exists",
00316               name.c_str());
00317     return false;
00318   }
00319 
00320   // Destroys the old controllers list when the realtime thread is finished with it.
00321   ROS_DEBUG("Realtime switches over to new controller list");
00322   int former_current_controllers_list_ = current_controllers_list_;
00323   current_controllers_list_ = free_controllers_list;
00324   while (ros::ok() && used_by_realtime_ == former_current_controllers_list_){
00325     if (!ros::ok())
00326       return false;
00327     usleep(200);
00328   }
00329   ROS_DEBUG("Destruct controller");
00330   from.clear();
00331   ROS_DEBUG("Destruct controller finished");
00332 
00333   ROS_DEBUG("Successfully unloaded controller '%s'", name.c_str());
00334   return true;
00335 }
00336 
00337 
00338 
00339 bool ControllerManager::switchController(const std::vector<std::string>& start_controllers,
00340                                          const std::vector<std::string>& stop_controllers,
00341                                          int strictness)
00342 {
00343   if (!stop_request_.empty() || !start_request_.empty())
00344     ROS_FATAL("The switch controller stop and start list are not empty that the beginning of the swithcontroller call. This should not happen.");
00345 
00346   if (strictness == 0){
00347     ROS_WARN("Controller Manager: To switch controllers you need to specify a strictness level of controller_manager_msgs::SwitchController::STRICT (%d) or ::BEST_EFFORT (%d). Defaulting to ::BEST_EFFORT.",
00348              controller_manager_msgs::SwitchController::Request::STRICT,
00349              controller_manager_msgs::SwitchController::Request::BEST_EFFORT);
00350     strictness = controller_manager_msgs::SwitchController::Request::BEST_EFFORT;
00351   }
00352 
00353   ROS_DEBUG("switching controllers:");
00354   for (unsigned int i=0; i<start_controllers.size(); i++)
00355     ROS_DEBUG(" - starting controller %s", start_controllers[i].c_str());
00356   for (unsigned int i=0; i<stop_controllers.size(); i++)
00357     ROS_DEBUG(" - stopping controller %s", stop_controllers[i].c_str());
00358 
00359   // lock controllers
00360   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00361 
00362   controller_interface::ControllerBase* ct;
00363   // list all controllers to stop
00364   for (unsigned int i=0; i<stop_controllers.size(); i++)
00365   {
00366     ct = getControllerByName(stop_controllers[i]);
00367     if (ct == NULL){
00368       if (strictness ==  controller_manager_msgs::SwitchController::Request::STRICT){
00369         ROS_ERROR("Could not stop controller with name %s because no controller with this name exists",
00370                   stop_controllers[i].c_str());
00371         stop_request_.clear();
00372         return false;
00373       }
00374       else{
00375         ROS_DEBUG("Could not stop controller with name %s because no controller with this name exists",
00376                   stop_controllers[i].c_str());
00377       }
00378     }
00379     else{
00380       ROS_DEBUG("Found controller %s that needs to be stopped in list of controllers",
00381                 stop_controllers[i].c_str());
00382       stop_request_.push_back(ct);
00383     }
00384   }
00385   ROS_DEBUG("Stop request vector has size %i", (int)stop_request_.size());
00386 
00387   // list all controllers to start
00388   for (unsigned int i=0; i<start_controllers.size(); i++)
00389   {
00390     ct = getControllerByName(start_controllers[i]);
00391     if (ct == NULL){
00392       if (strictness ==  controller_manager_msgs::SwitchController::Request::STRICT){
00393         ROS_ERROR("Could not start controller with name %s because no controller with this name exists",
00394                   start_controllers[i].c_str());
00395         stop_request_.clear();
00396         start_request_.clear();
00397         return false;
00398       }
00399       else{
00400         ROS_DEBUG("Could not start controller with name %s because no controller with this name exists",
00401                   start_controllers[i].c_str());
00402       }
00403     }
00404     else{
00405       ROS_DEBUG("Found controller %s that needs to be started in list of controllers",
00406                 start_controllers[i].c_str());
00407       start_request_.push_back(ct);
00408     }
00409   }
00410   ROS_DEBUG("Start request vector has size %i", (int)start_request_.size());
00411 
00412   // Do the resource management checking
00413   std::list<hardware_interface::ControllerInfo> info_list;
00414   switch_start_list_.clear();
00415   switch_stop_list_.clear();
00416   
00417   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00418   for (size_t i = 0; i < controllers.size(); ++i)
00419   {
00420     bool in_stop_list  = false;
00421     for(size_t j = 0; j < stop_request_.size(); j++)
00422     {
00423       if (stop_request_[j] == controllers[i].c.get())
00424       {
00425         in_stop_list = true;
00426         break;
00427       }
00428     }
00429 
00430     bool in_start_list = false;
00431     for(size_t j = 0; j < start_request_.size(); j++)
00432     {
00433       if (start_request_[j] == controllers[i].c.get())
00434       {
00435         in_start_list = true;
00436         break;
00437       }
00438     }
00439 
00440     const bool is_running = controllers[i].c->isRunning();
00441     hardware_interface::ControllerInfo &info = controllers[i].info;
00442 
00443     if(!is_running && in_stop_list){ // check for double stop
00444       if(strictness ==  controller_manager_msgs::SwitchController::Request::STRICT){
00445         ROS_ERROR_STREAM("Could not stop controller '" << info.name << "' since it is not running");
00446         stop_request_.clear();
00447         start_request_.clear();
00448         return false;
00449       } else {
00450         in_stop_list = false;
00451       }
00452     }
00453 
00454     if(is_running && !in_stop_list && in_start_list){ // check for doubled start
00455       if(strictness ==  controller_manager_msgs::SwitchController::Request::STRICT){
00456         ROS_ERROR_STREAM("Controller '" << info.name << "' is already running");
00457         stop_request_.clear();
00458         start_request_.clear();
00459         return false;
00460       } else {
00461         in_start_list = false;
00462       }
00463     }
00464 
00465     if(is_running && in_stop_list && !in_start_list){ // running and real stop
00466       switch_stop_list_.push_back(info);
00467     }
00468     else if(!is_running && !in_stop_list && in_start_list){ // start, but no restart
00469       switch_start_list_.push_back(info);
00470      }
00471 
00472     bool add_to_list = is_running;
00473     if (in_stop_list)
00474       add_to_list = false;
00475     if (in_start_list)
00476       add_to_list = true;
00477 
00478     if (add_to_list)
00479       info_list.push_back(info);
00480   }
00481 
00482   bool in_conflict = robot_hw_->checkForConflict(info_list);
00483   if (in_conflict)
00484   {
00485     ROS_ERROR("Could not switch controllers, due to resource conflict");
00486     stop_request_.clear();
00487     start_request_.clear();
00488     return false;
00489   }
00490 
00491   if (!robot_hw_->prepareSwitch(switch_start_list_, switch_stop_list_))
00492   {
00493     ROS_ERROR("Could not switch controllers. The hardware interface combination for the requested controllers is unfeasible.");
00494     stop_request_.clear();
00495     start_request_.clear();
00496     return false;
00497   }
00498 
00499   // start the atomic controller switching
00500   switch_strictness_ = strictness;
00501   please_switch_ = true;
00502 
00503   // wait until switch is finished
00504   ROS_DEBUG("Request atomic controller switch from realtime loop");
00505   while (ros::ok() && please_switch_){
00506     if (!ros::ok())
00507       return false;
00508     usleep(100);
00509   }
00510   start_request_.clear();
00511   stop_request_.clear();
00512 
00513   ROS_DEBUG("Successfully switched controllers");
00514   return true;
00515 }
00516 
00517 
00518 
00519 
00520 
00521 bool ControllerManager::reloadControllerLibrariesSrv(
00522   controller_manager_msgs::ReloadControllerLibraries::Request &req,
00523   controller_manager_msgs::ReloadControllerLibraries::Response &resp)
00524 {
00525   // lock services
00526   ROS_DEBUG("reload libraries service called");
00527   boost::mutex::scoped_lock guard(services_lock_);
00528   ROS_DEBUG("reload libraries service locked");
00529 
00530   // only reload libraries if no controllers are running
00531   std::vector<std::string> controllers;
00532   getControllerNames(controllers);
00533   if (!controllers.empty() && !req.force_kill){
00534     ROS_ERROR("Controller manager: Cannot reload controller libraries because there are still %i controllers running", (int)controllers.size());
00535     resp.ok = false;
00536     return true;
00537   }
00538 
00539   // kill running controllers if requested
00540   if (!controllers.empty()){
00541     ROS_INFO("Controller manager: Killing all running controllers");
00542     std::vector<std::string> empty;
00543     if (!switchController(empty,controllers, controller_manager_msgs::SwitchController::Request::BEST_EFFORT)){
00544       ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to stop running controllers");
00545       resp.ok = false;
00546       return true;
00547     }
00548     for (unsigned int i=0; i<controllers.size(); i++){
00549       if (!unloadController(controllers[i])){
00550         ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to unload controller %s",
00551                   controllers[i].c_str());
00552         resp.ok = false;
00553         return true;
00554       }
00555     }
00556     getControllerNames(controllers);
00557   }
00558   assert(controllers.empty());
00559 
00560   // Force a reload on all the PluginLoaders (internally, this recreates the plugin loaders)
00561   for(std::list<LoaderPtr>::iterator it = controller_loaders_.begin(); it != controller_loaders_.end(); ++it)
00562   {
00563     (*it)->reload();
00564     ROS_INFO("Controller manager: reloaded controller libraries for %s", (*it)->getName().c_str());
00565   }
00566 
00567   resp.ok = true;
00568 
00569   ROS_DEBUG("reload libraries service finished");
00570   return true;
00571 }
00572 
00573 
00574 bool ControllerManager::listControllerTypesSrv(
00575   controller_manager_msgs::ListControllerTypes::Request &req,
00576   controller_manager_msgs::ListControllerTypes::Response &resp)
00577 {
00578   // pretend to use the request
00579   (void) req;
00580 
00581   // lock services
00582   ROS_DEBUG("list types service called");
00583   boost::mutex::scoped_lock guard(services_lock_);
00584   ROS_DEBUG("list types service locked");
00585 
00586   for(std::list<LoaderPtr>::iterator it = controller_loaders_.begin(); it != controller_loaders_.end(); ++it)
00587   {
00588     std::vector<std::string> cur_types = (*it)->getDeclaredClasses();
00589     for(size_t i=0; i < cur_types.size(); i++)
00590     {
00591       resp.types.push_back(cur_types[i]);
00592       resp.base_classes.push_back((*it)->getName());
00593     }
00594   }
00595 
00596   ROS_DEBUG("list types service finished");
00597   return true;
00598 }
00599 
00600 
00601 bool ControllerManager::listControllersSrv(
00602   controller_manager_msgs::ListControllers::Request &req,
00603   controller_manager_msgs::ListControllers::Response &resp)
00604 {
00605   // pretend to use the request
00606   (void) req;
00607 
00608   // lock services
00609   ROS_DEBUG("list controller service called");
00610   boost::mutex::scoped_lock services_guard(services_lock_);
00611   ROS_DEBUG("list controller service locked");
00612 
00613   // lock controllers to get all names/types/states
00614   boost::recursive_mutex::scoped_lock controller_guard(controllers_lock_);
00615   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00616   resp.controller.resize(controllers.size());
00617 
00618   for (size_t i = 0; i < controllers.size(); ++i)
00619   {
00620     controller_manager_msgs::ControllerState& cs = resp.controller[i];
00621     cs.name = controllers[i].info.name;
00622     cs.type = controllers[i].info.type;
00623 
00624     cs.claimed_resources.clear();
00625     typedef std::vector<hardware_interface::InterfaceResources> ClaimedResVec;
00626     typedef ClaimedResVec::const_iterator ClaimedResIt;
00627     const ClaimedResVec& c_res = controllers[i].info.claimed_resources;
00628     for (ClaimedResIt c_res_it = c_res.begin(); c_res_it != c_res.end(); ++c_res_it)
00629     {
00630       controller_manager_msgs::HardwareInterfaceResources iface_res;
00631       iface_res.hardware_interface = c_res_it->hardware_interface;
00632       std::copy(c_res_it->resources.begin(), c_res_it->resources.end(), std::back_inserter(iface_res.resources));
00633       cs.claimed_resources.push_back(iface_res);
00634     }
00635 
00636     if (controllers[i].c->isRunning())
00637       cs.state = "running";
00638     else
00639       cs.state = "stopped";
00640   }
00641 
00642   ROS_DEBUG("list controller service finished");
00643   return true;
00644 }
00645 
00646 
00647 bool ControllerManager::loadControllerSrv(
00648   controller_manager_msgs::LoadController::Request &req,
00649   controller_manager_msgs::LoadController::Response &resp)
00650 {
00651   // lock services
00652   ROS_DEBUG("loading service called for controller %s ",req.name.c_str());
00653   boost::mutex::scoped_lock guard(services_lock_);
00654   ROS_DEBUG("loading service locked");
00655 
00656   resp.ok = loadController(req.name);
00657 
00658   ROS_DEBUG("loading service finished for controller %s ",req.name.c_str());
00659   return true;
00660 }
00661 
00662 
00663 bool ControllerManager::unloadControllerSrv(
00664   controller_manager_msgs::UnloadController::Request &req,
00665   controller_manager_msgs::UnloadController::Response &resp)
00666 {
00667   // lock services
00668   ROS_DEBUG("unloading service called for controller %s ",req.name.c_str());
00669   boost::mutex::scoped_lock guard(services_lock_);
00670   ROS_DEBUG("unloading service locked");
00671 
00672   resp.ok = unloadController(req.name);
00673 
00674   ROS_DEBUG("unloading service finished for controller %s ",req.name.c_str());
00675   return true;
00676 }
00677 
00678 
00679 bool ControllerManager::switchControllerSrv(
00680   controller_manager_msgs::SwitchController::Request &req,
00681   controller_manager_msgs::SwitchController::Response &resp)
00682 {
00683   // lock services
00684   ROS_DEBUG("switching service called");
00685   boost::mutex::scoped_lock guard(services_lock_);
00686   ROS_DEBUG("switching service locked");
00687 
00688   resp.ok = switchController(req.start_controllers, req.stop_controllers, req.strictness);
00689 
00690   ROS_DEBUG("switching service finished");
00691   return true;
00692 }
00693 
00694 void ControllerManager::registerControllerLoader(boost::shared_ptr<ControllerLoaderInterface> controller_loader)
00695 {
00696   controller_loaders_.push_back(controller_loader);
00697 }
00698 
00699 }


controller_manager
Author(s): Wim Meeussen, Mathias Lüdtke
autogenerated on Thu Dec 1 2016 03:46:00