controller_manager.cpp
Go to the documentation of this file.
1 // Copyright (C) 2012, hiDOF, INC and 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 names of Willow Garage, Inc., hiDOF 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  * Author: Wim Meeussen
29  */
30 
32 #include <algorithm>
33 #include <boost/thread/thread.hpp>
34 #include <boost/thread/condition.hpp>
35 #include <sstream>
36 #include <ros/console.h>
38 #include <controller_manager_msgs/ControllerState.h>
39 
40 namespace controller_manager{
41 
42 
44  robot_hw_(robot_hw),
45  root_nh_(nh),
46  cm_node_(nh, "controller_manager"),
47  start_request_(0),
48  stop_request_(0),
49  please_switch_(false),
50  current_controllers_list_(0),
51  used_by_realtime_(-1)
52 {
53  // create controller loader
54  controller_loaders_.push_back(
56  "controller_interface::ControllerBase") ) );
57 
58  // Advertise services (this should be the last thing we do in init)
65 }
66 
67 
69 {}
70 
71 
72 
73 
74 // Must be realtime safe.
75 void ControllerManager::update(const ros::Time& time, const ros::Duration& period, bool reset_controllers)
76 {
78  std::vector<ControllerSpec> &controllers = controllers_lists_[used_by_realtime_];
79 
80  // Restart all running controllers if motors are re-enabled
81  if (reset_controllers){
82  for (size_t i=0; i<controllers.size(); i++){
83  if (controllers[i].c->isRunning()){
84  controllers[i].c->stopRequest(time);
85  controllers[i].c->startRequest(time);
86  }
87  }
88  }
89 
90 
91  // Update all controllers
92  for (size_t i=0; i<controllers.size(); i++)
93  controllers[i].c->updateRequest(time, period);
94 
95  // there are controllers to start/stop
96  if (please_switch_)
97  {
98  // switch hardware interfaces (if any)
100 
101  // stop controllers
102  for (unsigned int i=0; i<stop_request_.size(); i++)
103  if (!stop_request_[i]->stopRequest(time))
104  ROS_FATAL("Failed to stop controller in realtime loop. This should never happen.");
105 
106  // start controllers
107  for (unsigned int i=0; i<start_request_.size(); i++)
108  if (!start_request_[i]->startRequest(time))
109  ROS_FATAL("Failed to start controller in realtime loop. This should never happen.");
110 
111  please_switch_ = false;
112  }
113 }
114 
116 {
117  // Lock recursive mutex in this context
118  boost::recursive_mutex::scoped_lock guard(controllers_lock_);
119 
120  std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
121  for (size_t i = 0; i < controllers.size(); ++i)
122  {
123  if (controllers[i].info.name == name)
124  return controllers[i].c.get();
125  }
126  return NULL;
127 }
128 
129 void ControllerManager::getControllerNames(std::vector<std::string> &names)
130 {
131  boost::recursive_mutex::scoped_lock guard(controllers_lock_);
132  names.clear();
133  std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
134  for (size_t i = 0; i < controllers.size(); ++i)
135  {
136  names.push_back(controllers[i].info.name);
137  }
138 }
139 
140 
141 bool ControllerManager::loadController(const std::string& name)
142 {
143  ROS_DEBUG("Will load controller '%s'", name.c_str());
144 
145  // lock controllers
146  boost::recursive_mutex::scoped_lock guard(controllers_lock_);
147 
148  // get reference to controller list
149  int free_controllers_list = (current_controllers_list_ + 1) % 2;
150  while (ros::ok() && free_controllers_list == used_by_realtime_){
151  if (!ros::ok())
152  return false;
153  usleep(200);
154  }
155  std::vector<ControllerSpec>
157  &to = controllers_lists_[free_controllers_list];
158  to.clear();
159 
160  // Copy all controllers from the 'from' list to the 'to' list
161  for (size_t i = 0; i < from.size(); ++i)
162  to.push_back(from[i]);
163 
164  // Checks that we're not duplicating controllers
165  for (size_t j = 0; j < to.size(); ++j)
166  {
167  if (to[j].info.name == name)
168  {
169  to.clear();
170  ROS_ERROR("A controller named '%s' was already loaded inside the controller manager", name.c_str());
171  return false;
172  }
173  }
174 
175  ros::NodeHandle c_nh;
176  // Constructs the controller
177  try{
178  c_nh = ros::NodeHandle(root_nh_, name);
179  }
180  catch(std::exception &e) {
181  ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s':\n%s", name.c_str(), e.what());
182  return false;
183  }
184  catch(...){
185  ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s'", name.c_str());
186  return false;
187  }
189  std::string type;
190  if (c_nh.getParam("type", type))
191  {
192  ROS_DEBUG("Constructing controller '%s' of type '%s'", name.c_str(), type.c_str());
193  try
194  {
195  // Trying loading the controller using all of our controller loaders. Exit once we've found the first valid loaded controller
196  std::list<ControllerLoaderInterfaceSharedPtr>::iterator it = controller_loaders_.begin();
197  while (!c && it != controller_loaders_.end())
198  {
199  std::vector<std::string> cur_types = (*it)->getDeclaredClasses();
200  for(size_t i=0; i < cur_types.size(); i++){
201  if (type == cur_types[i]){
202  c = (*it)->createInstance(type);
203  }
204  }
205  ++it;
206  }
207  }
208  catch (const std::runtime_error &ex)
209  {
210  ROS_ERROR("Could not load class %s: %s", type.c_str(), ex.what());
211  }
212  }
213  else
214  {
215  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());
216  to.clear();
217  return false;
218  }
219 
220  // checks if controller was constructed
221  if (!c)
222  {
223  ROS_ERROR("Could not load controller '%s' because controller type '%s' does not exist.", name.c_str(), type.c_str());
224  ROS_ERROR("Use 'rosservice call controller_manager/list_controller_types' to get the available types");
225  to.clear();
226  return false;
227  }
228 
229  // Initializes the controller
230  ROS_DEBUG("Initializing controller '%s'", name.c_str());
231  bool initialized;
232  controller_interface::ControllerBase::ClaimedResources claimed_resources; // Gets populated during initRequest call
233  try{
234  initialized = c->initRequest(robot_hw_, root_nh_, c_nh, claimed_resources);
235  }
236  catch(std::exception &e){
237  ROS_ERROR("Exception thrown while initializing controller %s.\n%s", name.c_str(), e.what());
238  initialized = false;
239  }
240  catch(...){
241  ROS_ERROR("Exception thrown while initializing controller %s", name.c_str());
242  initialized = false;
243  }
244  if (!initialized)
245  {
246  to.clear();
247  ROS_ERROR("Initializing controller '%s' failed", name.c_str());
248  return false;
249  }
250  ROS_DEBUG("Initialized controller '%s' successful", name.c_str());
251 
252  // Adds the controller to the new list
253  to.resize(to.size() + 1);
254  to.back().info.type = type;
255  to.back().info.name = name;
256  to.back().info.claimed_resources = claimed_resources;
257  to.back().c = c;
258 
259  // Destroys the old controllers list when the realtime thread is finished with it.
260  int former_current_controllers_list_ = current_controllers_list_;
261  current_controllers_list_ = free_controllers_list;
262  while (ros::ok() && used_by_realtime_ == former_current_controllers_list_){
263  if (!ros::ok())
264  return false;
265  usleep(200);
266  }
267  from.clear();
268 
269  ROS_DEBUG("Successfully load controller '%s'", name.c_str());
270  return true;
271 }
272 
273 
274 
275 
276 bool ControllerManager::unloadController(const std::string &name)
277 {
278  ROS_DEBUG("Will unload controller '%s'", name.c_str());
279 
280  // lock the controllers
281  boost::recursive_mutex::scoped_lock guard(controllers_lock_);
282 
283  // get reference to controller list
284  int free_controllers_list = (current_controllers_list_ + 1) % 2;
285  while (ros::ok() && free_controllers_list == used_by_realtime_){
286  if (!ros::ok())
287  return false;
288  usleep(200);
289  }
290  std::vector<ControllerSpec>
292  &to = controllers_lists_[free_controllers_list];
293  to.clear();
294 
295  // Transfers the running controllers over, skipping the one to be removed and the running ones.
296  bool removed = false;
297  for (size_t i = 0; i < from.size(); ++i)
298  {
299  if (from[i].info.name == name){
300  if (from[i].c->isRunning()){
301  to.clear();
302  ROS_ERROR("Could not unload controller with name %s because it is still running",
303  name.c_str());
304  return false;
305  }
306  removed = true;
307  }
308  else
309  to.push_back(from[i]);
310  }
311 
312  // Fails if we could not remove the controllers
313  if (!removed)
314  {
315  to.clear();
316  ROS_ERROR("Could not unload controller with name %s because no controller with this name exists",
317  name.c_str());
318  return false;
319  }
320 
321  // Destroys the old controllers list when the realtime thread is finished with it.
322  ROS_DEBUG("Realtime switches over to new controller list");
323  int former_current_controllers_list_ = current_controllers_list_;
324  current_controllers_list_ = free_controllers_list;
325  while (ros::ok() && used_by_realtime_ == former_current_controllers_list_){
326  if (!ros::ok())
327  return false;
328  usleep(200);
329  }
330  ROS_DEBUG("Destruct controller");
331  from.clear();
332  ROS_DEBUG("Destruct controller finished");
333 
334  ROS_DEBUG("Successfully unloaded controller '%s'", name.c_str());
335  return true;
336 }
337 
338 
339 
340 bool ControllerManager::switchController(const std::vector<std::string>& start_controllers,
341  const std::vector<std::string>& stop_controllers,
342  int strictness)
343 {
344  if (!stop_request_.empty() || !start_request_.empty())
345  ROS_FATAL("The internal stop and start request lists are not empty at the beginning of the swithController() call. This should not happen.");
346 
347  if (strictness == 0){
348  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.",
349  controller_manager_msgs::SwitchController::Request::STRICT,
350  controller_manager_msgs::SwitchController::Request::BEST_EFFORT);
351  strictness = controller_manager_msgs::SwitchController::Request::BEST_EFFORT;
352  }
353 
354  ROS_DEBUG("switching controllers:");
355  for (unsigned int i=0; i<start_controllers.size(); i++)
356  ROS_DEBUG(" - starting controller %s", start_controllers[i].c_str());
357  for (unsigned int i=0; i<stop_controllers.size(); i++)
358  ROS_DEBUG(" - stopping controller %s", stop_controllers[i].c_str());
359 
360  // lock controllers
361  boost::recursive_mutex::scoped_lock guard(controllers_lock_);
362 
364  // list all controllers to stop
365  for (unsigned int i=0; i<stop_controllers.size(); i++)
366  {
367  ct = getControllerByName(stop_controllers[i]);
368  if (ct == NULL){
369  if (strictness == controller_manager_msgs::SwitchController::Request::STRICT){
370  ROS_ERROR("Could not stop controller with name %s because no controller with this name exists",
371  stop_controllers[i].c_str());
372  stop_request_.clear();
373  return false;
374  }
375  else{
376  ROS_DEBUG("Could not stop controller with name %s because no controller with this name exists",
377  stop_controllers[i].c_str());
378  }
379  }
380  else{
381  ROS_DEBUG("Found controller %s that needs to be stopped in list of controllers",
382  stop_controllers[i].c_str());
383  stop_request_.push_back(ct);
384  }
385  }
386  ROS_DEBUG("Stop request vector has size %i", (int)stop_request_.size());
387 
388  // list all controllers to start
389  for (unsigned int i=0; i<start_controllers.size(); i++)
390  {
391  ct = getControllerByName(start_controllers[i]);
392  if (ct == NULL){
393  if (strictness == controller_manager_msgs::SwitchController::Request::STRICT){
394  ROS_ERROR("Could not start controller with name %s because no controller with this name exists",
395  start_controllers[i].c_str());
396  stop_request_.clear();
397  start_request_.clear();
398  return false;
399  }
400  else{
401  ROS_DEBUG("Could not start controller with name %s because no controller with this name exists",
402  start_controllers[i].c_str());
403  }
404  }
405  else{
406  ROS_DEBUG("Found controller %s that needs to be started in list of controllers",
407  start_controllers[i].c_str());
408  start_request_.push_back(ct);
409  }
410  }
411  ROS_DEBUG("Start request vector has size %i", (int)start_request_.size());
412 
413  // Do the resource management checking
414  std::list<hardware_interface::ControllerInfo> info_list;
415  switch_start_list_.clear();
416  switch_stop_list_.clear();
417 
418  std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
419  for (size_t i = 0; i < controllers.size(); ++i)
420  {
421  bool in_stop_list = false;
422  for(size_t j = 0; j < stop_request_.size(); j++)
423  {
424  if (stop_request_[j] == controllers[i].c.get())
425  {
426  in_stop_list = true;
427  break;
428  }
429  }
430 
431  bool in_start_list = false;
432  for(size_t j = 0; j < start_request_.size(); j++)
433  {
434  if (start_request_[j] == controllers[i].c.get())
435  {
436  in_start_list = true;
437  break;
438  }
439  }
440 
441  const bool is_running = controllers[i].c->isRunning();
442  hardware_interface::ControllerInfo &info = controllers[i].info;
443 
444  if(!is_running && in_stop_list){ // check for double stop
445  if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){
446  ROS_ERROR_STREAM("Could not stop controller '" << info.name << "' since it is not running");
447  stop_request_.clear();
448  start_request_.clear();
449  return false;
450  } else {
451  in_stop_list = false;
452  }
453  }
454 
455  if(is_running && !in_stop_list && in_start_list){ // check for doubled start
456  if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){
457  ROS_ERROR_STREAM("Controller '" << info.name << "' is already running");
458  stop_request_.clear();
459  start_request_.clear();
460  return false;
461  } else {
462  in_start_list = false;
463  }
464  }
465 
466  if(is_running && in_stop_list && !in_start_list){ // running and real stop
467  switch_stop_list_.push_back(info);
468  }
469  else if(!is_running && !in_stop_list && in_start_list){ // start, but no restart
470  switch_start_list_.push_back(info);
471  }
472 
473  bool add_to_list = is_running;
474  if (in_stop_list)
475  add_to_list = false;
476  if (in_start_list)
477  add_to_list = true;
478 
479  if (add_to_list)
480  info_list.push_back(info);
481  }
482 
483  bool in_conflict = robot_hw_->checkForConflict(info_list);
484  if (in_conflict)
485  {
486  ROS_ERROR("Could not switch controllers, due to resource conflict");
487  stop_request_.clear();
488  start_request_.clear();
489  return false;
490  }
491 
493  {
494  ROS_ERROR("Could not switch controllers. The hardware interface combination for the requested controllers is unfeasible.");
495  stop_request_.clear();
496  start_request_.clear();
497  return false;
498  }
499 
500  // start the atomic controller switching
501  switch_strictness_ = strictness;
502  please_switch_ = true;
503 
504  // wait until switch is finished
505  ROS_DEBUG("Request atomic controller switch from realtime loop");
506  while (ros::ok() && please_switch_){
507  if (!ros::ok())
508  return false;
509  usleep(100);
510  }
511  start_request_.clear();
512  stop_request_.clear();
513 
514  ROS_DEBUG("Successfully switched controllers");
515  return true;
516 }
517 
518 
519 
520 
521 
523  controller_manager_msgs::ReloadControllerLibraries::Request &req,
524  controller_manager_msgs::ReloadControllerLibraries::Response &resp)
525 {
526  // lock services
527  ROS_DEBUG("reload libraries service called");
528  boost::mutex::scoped_lock guard(services_lock_);
529  ROS_DEBUG("reload libraries service locked");
530 
531  // only reload libraries if no controllers are running
532  std::vector<std::string> controllers;
533  getControllerNames(controllers);
534  if (!controllers.empty() && !req.force_kill){
535  ROS_ERROR("Controller manager: Cannot reload controller libraries because there are still %i controllers running", (int)controllers.size());
536  resp.ok = false;
537  return true;
538  }
539 
540  // kill running controllers if requested
541  if (!controllers.empty()){
542  ROS_INFO("Controller manager: Killing all running controllers");
543  std::vector<std::string> empty;
544  if (!switchController(empty,controllers, controller_manager_msgs::SwitchController::Request::BEST_EFFORT)){
545  ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to stop running controllers");
546  resp.ok = false;
547  return true;
548  }
549  for (unsigned int i=0; i<controllers.size(); i++){
550  if (!unloadController(controllers[i])){
551  ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to unload controller %s",
552  controllers[i].c_str());
553  resp.ok = false;
554  return true;
555  }
556  }
557  getControllerNames(controllers);
558  }
559  assert(controllers.empty());
560 
561  // Force a reload on all the PluginLoaders (internally, this recreates the plugin loaders)
562  for(std::list<ControllerLoaderInterfaceSharedPtr>::iterator it = controller_loaders_.begin(); it != controller_loaders_.end(); ++it)
563  {
564  (*it)->reload();
565  ROS_INFO("Controller manager: reloaded controller libraries for %s", (*it)->getName().c_str());
566  }
567 
568  resp.ok = true;
569 
570  ROS_DEBUG("reload libraries service finished");
571  return true;
572 }
573 
574 
576  controller_manager_msgs::ListControllerTypes::Request &req,
577  controller_manager_msgs::ListControllerTypes::Response &resp)
578 {
579  // pretend to use the request
580  (void) req;
581 
582  // lock services
583  ROS_DEBUG("list types service called");
584  boost::mutex::scoped_lock guard(services_lock_);
585  ROS_DEBUG("list types service locked");
586 
587  for(std::list<ControllerLoaderInterfaceSharedPtr>::iterator it = controller_loaders_.begin(); it != controller_loaders_.end(); ++it)
588  {
589  std::vector<std::string> cur_types = (*it)->getDeclaredClasses();
590  for(size_t i=0; i < cur_types.size(); i++)
591  {
592  resp.types.push_back(cur_types[i]);
593  resp.base_classes.push_back((*it)->getName());
594  }
595  }
596 
597  ROS_DEBUG("list types service finished");
598  return true;
599 }
600 
601 
603  controller_manager_msgs::ListControllers::Request &req,
604  controller_manager_msgs::ListControllers::Response &resp)
605 {
606  // pretend to use the request
607  (void) req;
608 
609  // lock services
610  ROS_DEBUG("list controller service called");
611  boost::mutex::scoped_lock services_guard(services_lock_);
612  ROS_DEBUG("list controller service locked");
613 
614  // lock controllers to get all names/types/states
615  boost::recursive_mutex::scoped_lock controller_guard(controllers_lock_);
616  std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
617  resp.controller.resize(controllers.size());
618 
619  for (size_t i = 0; i < controllers.size(); ++i)
620  {
621  controller_manager_msgs::ControllerState& cs = resp.controller[i];
622  cs.name = controllers[i].info.name;
623  cs.type = controllers[i].info.type;
624 
625  cs.claimed_resources.clear();
626  typedef std::vector<hardware_interface::InterfaceResources> ClaimedResVec;
627  typedef ClaimedResVec::const_iterator ClaimedResIt;
628  const ClaimedResVec& c_res = controllers[i].info.claimed_resources;
629  for (ClaimedResIt c_res_it = c_res.begin(); c_res_it != c_res.end(); ++c_res_it)
630  {
631  controller_manager_msgs::HardwareInterfaceResources iface_res;
632  iface_res.hardware_interface = c_res_it->hardware_interface;
633  std::copy(c_res_it->resources.begin(), c_res_it->resources.end(), std::back_inserter(iface_res.resources));
634  cs.claimed_resources.push_back(iface_res);
635  }
636 
637  if (controllers[i].c->isRunning())
638  cs.state = "running";
639  else
640  cs.state = "stopped";
641  }
642 
643  ROS_DEBUG("list controller service finished");
644  return true;
645 }
646 
647 
649  controller_manager_msgs::LoadController::Request &req,
650  controller_manager_msgs::LoadController::Response &resp)
651 {
652  // lock services
653  ROS_DEBUG("loading service called for controller %s ",req.name.c_str());
654  boost::mutex::scoped_lock guard(services_lock_);
655  ROS_DEBUG("loading service locked");
656 
657  resp.ok = loadController(req.name);
658 
659  ROS_DEBUG("loading service finished for controller %s ",req.name.c_str());
660  return true;
661 }
662 
663 
665  controller_manager_msgs::UnloadController::Request &req,
666  controller_manager_msgs::UnloadController::Response &resp)
667 {
668  // lock services
669  ROS_DEBUG("unloading service called for controller %s ",req.name.c_str());
670  boost::mutex::scoped_lock guard(services_lock_);
671  ROS_DEBUG("unloading service locked");
672 
673  resp.ok = unloadController(req.name);
674 
675  ROS_DEBUG("unloading service finished for controller %s ",req.name.c_str());
676  return true;
677 }
678 
679 
681  controller_manager_msgs::SwitchController::Request &req,
682  controller_manager_msgs::SwitchController::Response &resp)
683 {
684  // lock services
685  ROS_DEBUG("switching service called");
686  boost::mutex::scoped_lock guard(services_lock_);
687  ROS_DEBUG("switching service locked");
688 
689  resp.ok = switchController(req.start_controllers, req.stop_controllers, req.strictness);
690 
691  ROS_DEBUG("switching service finished");
692  return true;
693 }
694 
696 {
697  controller_loaders_.push_back(controller_loader);
698 }
699 
700 }
bool switchControllerSrv(controller_manager_msgs::SwitchController::Request &req, controller_manager_msgs::SwitchController::Response &resp)
void getControllerNames(std::vector< std::string > &v)
bool loadControllerSrv(controller_manager_msgs::LoadController::Request &req, controller_manager_msgs::LoadController::Response &resp)
std::vector< controller_interface::ControllerBase * > stop_request_
#define ROS_FATAL(...)
virtual void doSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
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.
virtual bool checkForConflict(const std::list< ControllerInfo > &info) const
Pluginlib-Based Controller Loader.
int used_by_realtime_
The index of the controllers list being used in the real-time thread.
std::vector< hardware_interface::InterfaceResources > ClaimedResources
std::vector< ControllerSpec > controllers_lists_[2]
Double-buffered controllers list.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
hardware_interface::RobotHW * robot_hw_
#define ROS_WARN(...)
std::vector< controller_interface::ControllerBase * > start_request_
virtual bool prepareSwitch(const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
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.
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
const std::string & getNamespace() const
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.
boost::shared_ptr< ControllerLoaderInterface > ControllerLoaderInterfaceSharedPtr
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)
bool getParam(const std::string &key, std::string &s) const
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_
#define ROS_ERROR_STREAM(args)
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
Update all active controllers.
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


controller_manager
Author(s): Wim Meeussen, Mathias Lüdtke
autogenerated on Mon Apr 20 2020 03:52:09