controller_manager.h
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2012, hiDOF, INC & 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 name of hiDOF, Inc., Willow Garage, 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 /*
00029  * Author: Wim Meeussen
00030  */
00031 
00032 
00033 #ifndef CONTROLLER_MANAGER_CONTROLLER_MANAGER_H
00034 #define CONTROLLER_MANAGER_CONTROLLER_MANAGER_H
00035 
00036 #include "controller_manager/controller_spec.h"
00037 #include <pthread.h>
00038 #include <cstdio>
00039 #include <map>
00040 #include <string>
00041 #include <vector>
00042 #include <ros/ros.h>
00043 #include <tinyxml.h>
00044 #include <hardware_interface/robot_hw.h>
00045 #include <realtime_tools/realtime_publisher.h>
00046 #include <ros/node_handle.h>
00047 #include <pluginlib/class_loader.h>
00048 #include <controller_manager_msgs/ListControllerTypes.h>
00049 #include <controller_manager_msgs/ListControllers.h>
00050 #include <controller_manager_msgs/ReloadControllerLibraries.h>
00051 #include <controller_manager_msgs/LoadController.h>
00052 #include <controller_manager_msgs/UnloadController.h>
00053 #include <controller_manager_msgs/SwitchController.h>
00054 #include <boost/thread/condition.hpp>
00055 #include <boost/thread/recursive_mutex.hpp>
00056 #include <controller_manager/controller_loader_interface.h>
00057 
00058 
00059 namespace controller_manager{
00060 
00069 class ControllerManager{
00070 
00071 public:
00078   ControllerManager(hardware_interface::RobotHW *robot_hw,
00079                    const ros::NodeHandle& nh=ros::NodeHandle());
00080   virtual ~ControllerManager();
00081 
00094   void update(const ros::Time& time, const ros::Duration& period, bool reset_controllers=false);
00095   /*\}*/
00096 
00122   bool loadController(const std::string& name);
00123 
00129   bool unloadController(const std::string &name);
00130 
00141   bool switchController(const std::vector<std::string>& start_controllers,
00142                         const std::vector<std::string>& stop_controllers,
00143                         const int strictness);
00144 
00150   virtual controller_interface::ControllerBase* getControllerByName(const std::string& name);
00151 
00165   void registerControllerLoader(boost::shared_ptr<ControllerLoaderInterface> controller_loader);
00166   /*\}*/
00167 
00168 
00169 private:
00170   void getControllerNames(std::vector<std::string> &v);
00171 
00172   hardware_interface::RobotHW* robot_hw_;
00173 
00174   ros::NodeHandle root_nh_, cm_node_;
00175 
00176   typedef boost::shared_ptr<ControllerLoaderInterface> LoaderPtr;
00177   std::list<LoaderPtr> controller_loaders_;
00178 
00181   std::vector<controller_interface::ControllerBase*> start_request_, stop_request_;
00182   std::list<hardware_interface::ControllerInfo> switch_start_list_, switch_stop_list_;
00183   bool please_switch_;
00184   int switch_strictness_;
00185   /*\}*/
00186 
00191 
00192   boost::recursive_mutex controllers_lock_;
00194   std::vector<ControllerSpec> controllers_lists_[2];
00196   int current_controllers_list_;
00198   int used_by_realtime_;
00199   /*\}*/
00200 
00201 
00204   bool listControllerTypesSrv(controller_manager_msgs::ListControllerTypes::Request &req,
00205                               controller_manager_msgs::ListControllerTypes::Response &resp);
00206   bool listControllersSrv(controller_manager_msgs::ListControllers::Request &req,
00207                           controller_manager_msgs::ListControllers::Response &resp);
00208   bool switchControllerSrv(controller_manager_msgs::SwitchController::Request &req,
00209                            controller_manager_msgs::SwitchController::Response &resp);
00210   bool loadControllerSrv(controller_manager_msgs::LoadController::Request &req,
00211                           controller_manager_msgs::LoadController::Response &resp);
00212   bool unloadControllerSrv(controller_manager_msgs::UnloadController::Request &req,
00213                          controller_manager_msgs::UnloadController::Response &resp);
00214   bool reloadControllerLibrariesSrv(controller_manager_msgs::ReloadControllerLibraries::Request &req,
00215                                     controller_manager_msgs::ReloadControllerLibraries::Response &resp);
00216   boost::mutex services_lock_;
00217   ros::ServiceServer srv_list_controllers_, srv_list_controller_types_, srv_load_controller_;
00218   ros::ServiceServer srv_unload_controller_, srv_switch_controller_, srv_reload_libraries_;
00219   /*\}*/
00220 };
00221 
00222 }
00223 #endif


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