Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00027
00028
00029
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 bool please_switch_;
00183 int switch_strictness_;
00184
00185
00190
00191 boost::recursive_mutex controllers_lock_;
00193 std::vector<ControllerSpec> controllers_lists_[2];
00195 int current_controllers_list_;
00197 int used_by_realtime_;
00198
00199
00200
00203 bool listControllerTypesSrv(controller_manager_msgs::ListControllerTypes::Request &req,
00204 controller_manager_msgs::ListControllerTypes::Response &resp);
00205 bool listControllersSrv(controller_manager_msgs::ListControllers::Request &req,
00206 controller_manager_msgs::ListControllers::Response &resp);
00207 bool switchControllerSrv(controller_manager_msgs::SwitchController::Request &req,
00208 controller_manager_msgs::SwitchController::Response &resp);
00209 bool loadControllerSrv(controller_manager_msgs::LoadController::Request &req,
00210 controller_manager_msgs::LoadController::Response &resp);
00211 bool unloadControllerSrv(controller_manager_msgs::UnloadController::Request &req,
00212 controller_manager_msgs::UnloadController::Response &resp);
00213 bool reloadControllerLibrariesSrv(controller_manager_msgs::ReloadControllerLibraries::Request &req,
00214 controller_manager_msgs::ReloadControllerLibraries::Response &resp);
00215 boost::mutex services_lock_;
00216 ros::ServiceServer srv_list_controllers_, srv_list_controller_types_, srv_load_controller_;
00217 ros::ServiceServer srv_unload_controller_, srv_switch_controller_, srv_reload_libraries_;
00218
00219 };
00220
00221 }
00222 #endif