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     // stop controllers
00098     for (unsigned int i=0; i<stop_request_.size(); i++)
00099       if (!stop_request_[i]->stopRequest(time))
00100         ROS_FATAL("Failed to stop controller in realtime loop. This should never happen.");
00101 
00102     // start controllers
00103     for (unsigned int i=0; i<start_request_.size(); i++)
00104       if (!start_request_[i]->startRequest(time))
00105         ROS_FATAL("Failed to start controller in realtime loop. This should never happen.");
00106 
00107     please_switch_ = false;
00108   }
00109 }
00110 
00111 controller_interface::ControllerBase* ControllerManager::getControllerByName(const std::string& name)
00112 {
00113   // Lock recursive mutex in this context
00114   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00115 
00116   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00117   for (size_t i = 0; i < controllers.size(); ++i)
00118   {
00119     if (controllers[i].info.name == name)
00120       return controllers[i].c.get();
00121   }
00122   return NULL;
00123 }
00124 
00125 void ControllerManager::getControllerNames(std::vector<std::string> &names)
00126 {
00127   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00128   names.clear();
00129   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00130   for (size_t i = 0; i < controllers.size(); ++i)
00131   {
00132     names.push_back(controllers[i].info.name);
00133   }
00134 }
00135 
00136 
00137 bool ControllerManager::loadController(const std::string& name)
00138 {
00139   ROS_DEBUG("Will load controller '%s'", name.c_str());
00140 
00141   // lock controllers
00142   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00143 
00144   // get reference to controller list
00145   int free_controllers_list = (current_controllers_list_ + 1) % 2;
00146   while (ros::ok() && free_controllers_list == used_by_realtime_){
00147     if (!ros::ok())
00148       return false;
00149     usleep(200);
00150   }
00151   std::vector<ControllerSpec>
00152     &from = controllers_lists_[current_controllers_list_],
00153     &to = controllers_lists_[free_controllers_list];
00154   to.clear();
00155 
00156   // Copy all controllers from the 'from' list to the 'to' list
00157   for (size_t i = 0; i < from.size(); ++i)
00158     to.push_back(from[i]);
00159 
00160   // Checks that we're not duplicating controllers
00161   for (size_t j = 0; j < to.size(); ++j)
00162   {
00163     if (to[j].info.name == name)
00164     {
00165       to.clear();
00166       ROS_ERROR("A controller named '%s' was already loaded inside the controller manager", name.c_str());
00167       return false;
00168     }
00169   }
00170 
00171   ros::NodeHandle c_nh;
00172   // Constructs the controller
00173   try{
00174     c_nh = ros::NodeHandle(root_nh_, name);
00175   }
00176   catch(std::exception &e) {
00177     ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s':\n%s", name.c_str(), e.what());
00178     return false;
00179   }
00180   catch(...){
00181     ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s'", name.c_str());
00182     return false;
00183   }
00184   boost::shared_ptr<controller_interface::ControllerBase> c;
00185   std::string type;
00186   if (c_nh.getParam("type", type))
00187   {
00188     ROS_DEBUG("Constructing controller '%s' of type '%s'", name.c_str(), type.c_str());
00189     try
00190     {
00191       // Trying loading the controller using all of our controller loaders. Exit once we've found the first valid loaded controller
00192       std::list<LoaderPtr>::iterator it = controller_loaders_.begin();
00193       while (!c && it != controller_loaders_.end())
00194       {
00195         std::vector<std::string> cur_types = (*it)->getDeclaredClasses();
00196         for(size_t i=0; i < cur_types.size(); i++){
00197           if (type == cur_types[i]){
00198             c = (*it)->createInstance(type);
00199           }
00200         }
00201         ++it;
00202       }
00203     }
00204     catch (const std::runtime_error &ex)
00205     {
00206       ROS_ERROR("Could not load class %s: %s", type.c_str(), ex.what());
00207     }
00208   }
00209   else
00210   {
00211     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());
00212     to.clear();
00213     return false;
00214   }
00215 
00216   // checks if controller was constructed
00217   if (!c)
00218   {
00219     ROS_ERROR("Could not load controller '%s' because controller type '%s' does not exist.",  name.c_str(), type.c_str());
00220     ROS_ERROR("Use 'rosservice call controller_manager/list_controller_types' to get the available types");
00221     to.clear();
00222     return false;
00223   }
00224 
00225   // Initializes the controller
00226   ROS_DEBUG("Initializing controller '%s'", name.c_str());
00227   bool initialized;
00228   std::set<std::string> claimed_resources; // Gets populated during initRequest call
00229   try{
00230     initialized = c->initRequest(robot_hw_, root_nh_, c_nh, claimed_resources);
00231   }
00232   catch(std::exception &e){
00233     ROS_ERROR("Exception thrown while initializing controller %s.\n%s", name.c_str(), e.what());
00234     initialized = false;
00235   }
00236   catch(...){
00237     ROS_ERROR("Exception thrown while initializing controller %s", name.c_str());
00238     initialized = false;
00239   }
00240   if (!initialized)
00241   {
00242     to.clear();
00243     ROS_ERROR("Initializing controller '%s' failed", name.c_str());
00244     return false;
00245   }
00246   ROS_DEBUG("Initialized controller '%s' succesful", name.c_str());
00247 
00248   // Adds the controller to the new list
00249   to.resize(to.size() + 1);
00250   to[to.size()-1].info.type = type;
00251   to[to.size()-1].info.hardware_interface = c->getHardwareInterfaceType();
00252   to[to.size()-1].info.name = name;
00253   to[to.size()-1].info.resources = claimed_resources;
00254   to[to.size()-1].c = c;
00255 
00256   // Destroys the old controllers list when the realtime thread is finished with it.
00257   int former_current_controllers_list_ = current_controllers_list_;
00258   current_controllers_list_ = free_controllers_list;
00259   while (ros::ok() && used_by_realtime_ == former_current_controllers_list_){
00260     if (!ros::ok())
00261       return false;
00262     usleep(200);
00263   }
00264   from.clear();
00265 
00266   ROS_DEBUG("Successfully load controller '%s'", name.c_str());
00267   return true;
00268 }
00269 
00270 
00271 
00272 
00273 bool ControllerManager::unloadController(const std::string &name)
00274 {
00275   ROS_DEBUG("Will unload controller '%s'", name.c_str());
00276 
00277   // lock the controllers
00278   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00279 
00280   // get reference to controller list
00281   int free_controllers_list = (current_controllers_list_ + 1) % 2;
00282   while (ros::ok() && free_controllers_list == used_by_realtime_){
00283     if (!ros::ok())
00284       return false;
00285     usleep(200);
00286   }
00287   std::vector<ControllerSpec>
00288     &from = controllers_lists_[current_controllers_list_],
00289     &to = controllers_lists_[free_controllers_list];
00290   to.clear();
00291 
00292   // Transfers the running controllers over, skipping the one to be removed and the running ones.
00293   bool removed = false;
00294   for (size_t i = 0; i < from.size(); ++i)
00295   {
00296     if (from[i].info.name == name){
00297       if (from[i].c->isRunning()){
00298         to.clear();
00299         ROS_ERROR("Could not unload controller with name %s because it is still running",
00300                   name.c_str());
00301         return false;
00302       }
00303       removed = true;
00304     }
00305     else
00306       to.push_back(from[i]);
00307   }
00308 
00309   // Fails if we could not remove the controllers
00310   if (!removed)
00311   {
00312     to.clear();
00313     ROS_ERROR("Could not unload controller with name %s because no controller with this name exists",
00314               name.c_str());
00315     return false;
00316   }
00317 
00318   // Destroys the old controllers list when the realtime thread is finished with it.
00319   ROS_DEBUG("Realtime switches over to new controller list");
00320   int former_current_controllers_list_ = current_controllers_list_;
00321   current_controllers_list_ = free_controllers_list;
00322   while (ros::ok() && used_by_realtime_ == former_current_controllers_list_){
00323     if (!ros::ok())
00324       return false;
00325     usleep(200);
00326   }
00327   ROS_DEBUG("Destruct controller");
00328   from.clear();
00329   ROS_DEBUG("Destruct controller finished");
00330 
00331   ROS_DEBUG("Successfully unloaded controller '%s'", name.c_str());
00332   return true;
00333 }
00334 
00335 
00336 
00337 bool ControllerManager::switchController(const std::vector<std::string>& start_controllers,
00338                                          const std::vector<std::string>& stop_controllers,
00339                                          int strictness)
00340 {
00341   if (!stop_request_.empty() || !start_request_.empty())
00342     ROS_FATAL("The switch controller stop and start list are not empty that the beginning of the swithcontroller call. This should not happen.");
00343 
00344   if (strictness == 0){
00345     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.",
00346              controller_manager_msgs::SwitchController::Request::STRICT,
00347              controller_manager_msgs::SwitchController::Request::BEST_EFFORT);
00348     strictness = controller_manager_msgs::SwitchController::Request::BEST_EFFORT;
00349   }
00350 
00351   ROS_DEBUG("switching controllers:");
00352   for (unsigned int i=0; i<start_controllers.size(); i++)
00353     ROS_DEBUG(" - starting controller %s", start_controllers[i].c_str());
00354   for (unsigned int i=0; i<stop_controllers.size(); i++)
00355     ROS_DEBUG(" - stopping controller %s", stop_controllers[i].c_str());
00356 
00357   // lock controllers
00358   boost::recursive_mutex::scoped_lock guard(controllers_lock_);
00359 
00360   controller_interface::ControllerBase* ct;
00361   // list all controllers to stop
00362   for (unsigned int i=0; i<stop_controllers.size(); i++)
00363   {
00364     ct = getControllerByName(stop_controllers[i]);
00365     if (ct == NULL){
00366       if (strictness ==  controller_manager_msgs::SwitchController::Request::STRICT){
00367         ROS_ERROR("Could not stop controller with name %s because no controller with this name exists",
00368                   stop_controllers[i].c_str());
00369         stop_request_.clear();
00370         return false;
00371       }
00372       else{
00373         ROS_DEBUG("Could not stop controller with name %s because no controller with this name exists",
00374                   stop_controllers[i].c_str());
00375       }
00376     }
00377     else{
00378       ROS_DEBUG("Found controller %s that needs to be stopped in list of controllers",
00379                 stop_controllers[i].c_str());
00380       stop_request_.push_back(ct);
00381     }
00382   }
00383   ROS_DEBUG("Stop request vector has size %i", (int)stop_request_.size());
00384 
00385   // list all controllers to start
00386   for (unsigned int i=0; i<start_controllers.size(); i++)
00387   {
00388     ct = getControllerByName(start_controllers[i]);
00389     if (ct == NULL){
00390       if (strictness ==  controller_manager_msgs::SwitchController::Request::STRICT){
00391         ROS_ERROR("Could not start controller with name %s because no controller with this name exists",
00392                   start_controllers[i].c_str());
00393         stop_request_.clear();
00394         start_request_.clear();
00395         return false;
00396       }
00397       else{
00398         ROS_DEBUG("Could not start controller with name %s because no controller with this name exists",
00399                   start_controllers[i].c_str());
00400       }
00401     }
00402     else{
00403       ROS_DEBUG("Found controller %s that needs to be started in list of controllers",
00404                 start_controllers[i].c_str());
00405       start_request_.push_back(ct);
00406     }
00407   }
00408   ROS_DEBUG("Start request vector has size %i", (int)start_request_.size());
00409 
00410   // Do the resource management checking
00411   std::list<hardware_interface::ControllerInfo> info_list;
00412   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00413   for (size_t i = 0; i < controllers.size(); ++i)
00414   {
00415     bool in_stop_list  = false;
00416 
00417     for(size_t j = 0; j < stop_request_.size(); j++)
00418       in_stop_list = in_stop_list || (stop_request_[j] == controllers[i].c.get());
00419 
00420     bool in_start_list = false;
00421     for(size_t j = 0; j < start_request_.size(); j++)
00422       in_start_list = in_start_list || (start_request_[j] == controllers[i].c.get());
00423 
00424     bool add_to_list = controllers[i].c->isRunning();
00425     if (in_stop_list)
00426       add_to_list = false;
00427     if (in_start_list)
00428       add_to_list = true;
00429 
00430     if (add_to_list)
00431       info_list.push_back(controllers[i].info);
00432   }
00433 
00434   bool in_conflict = robot_hw_->checkForConflict(info_list);
00435   if (in_conflict)
00436   {
00437     ROS_ERROR("Could not switch controllers, due to resource conflict");
00438     stop_request_.clear();
00439     start_request_.clear();
00440     return false;
00441   }
00442 
00443   // start the atomic controller switching
00444   switch_strictness_ = strictness;
00445   please_switch_ = true;
00446 
00447   // wait until switch is finished
00448   ROS_DEBUG("Request atomic controller switch from realtime loop");
00449   while (ros::ok() && please_switch_){
00450     if (!ros::ok())
00451       return false;
00452     usleep(100);
00453   }
00454   start_request_.clear();
00455   stop_request_.clear();
00456 
00457   ROS_DEBUG("Successfully switched controllers");
00458   return true;
00459 }
00460 
00461 
00462 
00463 
00464 
00465 bool ControllerManager::reloadControllerLibrariesSrv(
00466   controller_manager_msgs::ReloadControllerLibraries::Request &req,
00467   controller_manager_msgs::ReloadControllerLibraries::Response &resp)
00468 {
00469   // lock services
00470   ROS_DEBUG("reload libraries service called");
00471   boost::mutex::scoped_lock guard(services_lock_);
00472   ROS_DEBUG("reload libraries service locked");
00473 
00474   // only reload libraries if no controllers are running
00475   std::vector<std::string> controllers;
00476   getControllerNames(controllers);
00477   if (!controllers.empty() && !req.force_kill){
00478     ROS_ERROR("Controller manager: Cannot reload controller libraries because there are still %i controllers running", (int)controllers.size());
00479     resp.ok = false;
00480     return true;
00481   }
00482 
00483   // kill running controllers if requested
00484   if (!controllers.empty()){
00485     ROS_INFO("Controller manager: Killing all running controllers");
00486     std::vector<std::string> empty;
00487     if (!switchController(empty,controllers, controller_manager_msgs::SwitchController::Request::BEST_EFFORT)){
00488       ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to stop running controllers");
00489       resp.ok = false;
00490       return true;
00491     }
00492     for (unsigned int i=0; i<controllers.size(); i++){
00493       if (!unloadController(controllers[i])){
00494         ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to unload controller %s",
00495                   controllers[i].c_str());
00496         resp.ok = false;
00497         return true;
00498       }
00499     }
00500     getControllerNames(controllers);
00501   }
00502   assert(controllers.empty());
00503 
00504   // Force a reload on all the PluginLoaders (internally, this recreates the plugin loaders)
00505   for(std::list<LoaderPtr>::iterator it = controller_loaders_.begin(); it != controller_loaders_.end(); ++it)
00506   {
00507     (*it)->reload();
00508     ROS_INFO("Controller manager: reloaded controller libraries for %s", (*it)->getName().c_str());
00509   }
00510 
00511   resp.ok = true;
00512 
00513   ROS_DEBUG("reload libraries service finished");
00514   return true;
00515 }
00516 
00517 
00518 bool ControllerManager::listControllerTypesSrv(
00519   controller_manager_msgs::ListControllerTypes::Request &req,
00520   controller_manager_msgs::ListControllerTypes::Response &resp)
00521 {
00522   // pretend to use the request
00523   (void) req;
00524 
00525   // lock services
00526   ROS_DEBUG("list types service called");
00527   boost::mutex::scoped_lock guard(services_lock_);
00528   ROS_DEBUG("list types service locked");
00529 
00530   for(std::list<LoaderPtr>::iterator it = controller_loaders_.begin(); it != controller_loaders_.end(); ++it)
00531   {
00532     std::vector<std::string> cur_types = (*it)->getDeclaredClasses();
00533     for(size_t i=0; i < cur_types.size(); i++)
00534     {
00535       resp.types.push_back(cur_types[i]);
00536       resp.base_classes.push_back((*it)->getName());
00537     }
00538   }
00539 
00540   ROS_DEBUG("list types service finished");
00541   return true;
00542 }
00543 
00544 
00545 bool ControllerManager::listControllersSrv(
00546   controller_manager_msgs::ListControllers::Request &req,
00547   controller_manager_msgs::ListControllers::Response &resp)
00548 {
00549   // pretend to use the request
00550   (void) req;
00551 
00552   // lock services
00553   ROS_DEBUG("list controller service called");
00554   boost::mutex::scoped_lock services_guard(services_lock_);
00555   ROS_DEBUG("list controller service locked");
00556 
00557   // lock controllers to get all names/types/states
00558   boost::recursive_mutex::scoped_lock controller_guard(controllers_lock_);
00559   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00560   resp.controller.resize(controllers.size());
00561 
00562   for (size_t i = 0; i < controllers.size(); ++i)
00563   {
00564     controller_manager_msgs::ControllerState& cs = resp.controller[i];
00565     cs.name               = controllers[i].info.name;
00566     cs.type               = controllers[i].info.type;
00567     cs.hardware_interface = controllers[i].info.hardware_interface;
00568     cs.resources.clear();
00569     cs.resources.reserve(controllers[i].info.resources.size());
00570     for (std::set<std::string>::iterator it = controllers[i].info.resources.begin(); it != controllers[i].info.resources.end(); ++it)
00571       cs.resources.push_back(*it);
00572 
00573     if (controllers[i].c->isRunning())
00574       cs.state = "running";
00575     else
00576       cs.state = "stopped";
00577   }
00578 
00579   ROS_DEBUG("list controller service finished");
00580   return true;
00581 }
00582 
00583 
00584 bool ControllerManager::loadControllerSrv(
00585   controller_manager_msgs::LoadController::Request &req,
00586   controller_manager_msgs::LoadController::Response &resp)
00587 {
00588   // lock services
00589   ROS_DEBUG("loading service called for controller %s ",req.name.c_str());
00590   boost::mutex::scoped_lock guard(services_lock_);
00591   ROS_DEBUG("loading service locked");
00592 
00593   resp.ok = loadController(req.name);
00594 
00595   ROS_DEBUG("loading service finished for controller %s ",req.name.c_str());
00596   return true;
00597 }
00598 
00599 
00600 bool ControllerManager::unloadControllerSrv(
00601   controller_manager_msgs::UnloadController::Request &req,
00602   controller_manager_msgs::UnloadController::Response &resp)
00603 {
00604   // lock services
00605   ROS_DEBUG("unloading service called for controller %s ",req.name.c_str());
00606   boost::mutex::scoped_lock guard(services_lock_);
00607   ROS_DEBUG("unloading service locked");
00608 
00609   resp.ok = unloadController(req.name);
00610 
00611   ROS_DEBUG("unloading service finished for controller %s ",req.name.c_str());
00612   return true;
00613 }
00614 
00615 
00616 bool ControllerManager::switchControllerSrv(
00617   controller_manager_msgs::SwitchController::Request &req,
00618   controller_manager_msgs::SwitchController::Response &resp)
00619 {
00620   // lock services
00621   ROS_DEBUG("switching service called");
00622   boost::mutex::scoped_lock guard(services_lock_);
00623   ROS_DEBUG("switching service locked");
00624 
00625   resp.ok = switchController(req.start_controllers, req.stop_controllers, req.strictness);
00626 
00627   ROS_DEBUG("switching service finished");
00628   return true;
00629 }
00630 
00631 void ControllerManager::registerControllerLoader(boost::shared_ptr<ControllerLoaderInterface> controller_loader)
00632 {
00633   controller_loaders_.push_back(controller_loader);
00634 }
00635 
00636 }


controller_manager
Author(s): Wim Meeussen
autogenerated on Fri Aug 28 2015 12:36:18