controller_manager.h
Go to the documentation of this file.
1 // Copyright (C) 2012, hiDOF, INC & Willow Garage, Inc
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of hiDOF, Inc., Willow Garage, Inc., nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
28 /*
29  * Author: Wim Meeussen
30  */
31 
32 
33 #ifndef CONTROLLER_MANAGER_CONTROLLER_MANAGER_H
34 #define CONTROLLER_MANAGER_CONTROLLER_MANAGER_H
35 
37 #include <pthread.h>
38 #include <cstdio>
39 #include <map>
40 #include <string>
41 #include <vector>
42 #include <ros/ros.h>
44 #include <ros/node_handle.h>
46 #include <controller_manager_msgs/ListControllerTypes.h>
47 #include <controller_manager_msgs/ListControllers.h>
48 #include <controller_manager_msgs/ReloadControllerLibraries.h>
49 #include <controller_manager_msgs/LoadController.h>
50 #include <controller_manager_msgs/UnloadController.h>
51 #include <controller_manager_msgs/SwitchController.h>
52 #include <boost/thread/condition.hpp>
53 #include <boost/thread/recursive_mutex.hpp>
55 
56 
57 namespace controller_manager{
58 
68 
69 public:
77  const ros::NodeHandle& nh=ros::NodeHandle());
78  virtual ~ControllerManager();
79 
92  void update(const ros::Time& time, const ros::Duration& period, bool reset_controllers=false);
93  /*\}*/
94 
120  bool loadController(const std::string& name);
121 
127  bool unloadController(const std::string &name);
128 
139  bool switchController(const std::vector<std::string>& start_controllers,
140  const std::vector<std::string>& stop_controllers,
141  const int strictness);
142 
148  virtual controller_interface::ControllerBase* getControllerByName(const std::string& name);
149 
164  /*\}*/
165 
166 
167 private:
168  void getControllerNames(std::vector<std::string> &v);
169 
171 
173 
174  std::list<ControllerLoaderInterfaceSharedPtr> controller_loaders_;
175 
178  std::vector<controller_interface::ControllerBase*> start_request_, stop_request_;
179  std::list<hardware_interface::ControllerInfo> switch_start_list_, switch_stop_list_;
182  /*\}*/
183 
188  boost::recursive_mutex controllers_lock_;
191  std::vector<ControllerSpec> controllers_lists_[2];
196  /*\}*/
197 
198 
201  bool listControllerTypesSrv(controller_manager_msgs::ListControllerTypes::Request &req,
202  controller_manager_msgs::ListControllerTypes::Response &resp);
203  bool listControllersSrv(controller_manager_msgs::ListControllers::Request &req,
204  controller_manager_msgs::ListControllers::Response &resp);
205  bool switchControllerSrv(controller_manager_msgs::SwitchController::Request &req,
206  controller_manager_msgs::SwitchController::Response &resp);
207  bool loadControllerSrv(controller_manager_msgs::LoadController::Request &req,
208  controller_manager_msgs::LoadController::Response &resp);
209  bool unloadControllerSrv(controller_manager_msgs::UnloadController::Request &req,
210  controller_manager_msgs::UnloadController::Response &resp);
211  bool reloadControllerLibrariesSrv(controller_manager_msgs::ReloadControllerLibraries::Request &req,
212  controller_manager_msgs::ReloadControllerLibraries::Response &resp);
213  boost::mutex services_lock_;
216  /*\}*/
217 };
218 
219 }
220 #endif
bool switchControllerSrv(controller_manager_msgs::SwitchController::Request &req, controller_manager_msgs::SwitchController::Response &resp)
void getControllerNames(std::vector< std::string > &v)
ROS Controller Manager and Runner.
bool loadControllerSrv(controller_manager_msgs::LoadController::Request &req, controller_manager_msgs::LoadController::Response &resp)
std::vector< controller_interface::ControllerBase * > stop_request_
bool loadController(const std::string &name)
Load a new controller by name.
bool switchController(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers, const int strictness)
Switch multiple controllers simultaneously.
int used_by_realtime_
The index of the controllers list being used in the real-time thread.
std::vector< ControllerSpec > controllers_lists_[2]
Double-buffered controllers list.
hardware_interface::RobotHW * robot_hw_
std::vector< controller_interface::ControllerBase * > start_request_
bool listControllerTypesSrv(controller_manager_msgs::ListControllerTypes::Request &req, controller_manager_msgs::ListControllerTypes::Response &resp)
virtual controller_interface::ControllerBase * getControllerByName(const std::string &name)
Get a controller by name.
bool unloadController(const std::string &name)
Unload a controller by name.
bool listControllersSrv(controller_manager_msgs::ListControllers::Request &req, controller_manager_msgs::ListControllers::Response &resp)
bool unloadControllerSrv(controller_manager_msgs::UnloadController::Request &req, controller_manager_msgs::UnloadController::Response &resp)
boost::recursive_mutex controllers_lock_
Mutex protecting the current controllers list.
std::list< ControllerLoaderInterfaceSharedPtr > controller_loaders_
std::list< hardware_interface::ControllerInfo > switch_start_list_
int current_controllers_list_
The index of the current controllers list.
bool reloadControllerLibrariesSrv(controller_manager_msgs::ReloadControllerLibraries::Request &req, controller_manager_msgs::ReloadControllerLibraries::Response &resp)
ControllerManager(hardware_interface::RobotHW *robot_hw, const ros::NodeHandle &nh=ros::NodeHandle())
Constructor.
void registerControllerLoader(ControllerLoaderInterfaceSharedPtr controller_loader)
Register a controller loader.
std::list< hardware_interface::ControllerInfo > switch_stop_list_
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
Update all active controllers.


controller_manager
Author(s): Wim Meeussen, Mathias Lüdtke
autogenerated on Fri Jun 7 2019 22:00:08