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 <chrono>
34 #include <mutex>
35 #include <sstream>
36 #include <thread>
37 #include <ros/console.h>
39 #include <controller_manager_msgs/ControllerState.h>
40 
41 namespace controller_manager
42 {
43 
44 
46  robot_hw_(robot_hw),
47  root_nh_(nh),
48  cm_node_(nh, "controller_manager")
49 {
50  // create controller loader
51  controller_loaders_.push_back(
53  "controller_interface::ControllerBase") ) );
54 
55  // Advertise services (this should be the last thing we do in init)
62 }
63 
64 
65 // Must be realtime safe.
66 void ControllerManager::update(const ros::Time& time, const ros::Duration& period, bool reset_controllers)
67 {
69 
70  // Restart all running controllers if motors are re-enabled
71  if (reset_controllers){
72  for (const auto& controller : controllers_lists_[used_by_realtime_]){
73  if (controller.c->isRunning()){
74  controller.c->stopRequest(time);
75  controller.c->startRequest(time);
76  }
77  }
78  }
79 
80 
81  // Update all controllers
82  for (const auto& controller : controllers_lists_[used_by_realtime_])
83  controller.c->updateRequest(time, period);
84 
85  // there are controllers to start/stop
87  {
88  manageSwitch(time);
89  }
90 }
91 
93 {
94  // Lock recursive mutex in this context
95  std::lock_guard<std::recursive_mutex> guard(controllers_lock_);
96 
97  for (const auto& controller : controllers_lists_[current_controllers_list_])
98  {
99  if (controller.info.name == name)
100  return controller.c.get();
101  }
102  return nullptr;
103 }
104 
105 void ControllerManager::getControllerNames(std::vector<std::string> &names)
106 {
107  std::lock_guard<std::recursive_mutex> guard(controllers_lock_);
108  names.clear();
109  for (const auto& controller : controllers_lists_[current_controllers_list_])
110  {
111  names.push_back(controller.info.name);
112  }
113 }
114 
116 {
117  // switch hardware interfaces (if any)
118  if (!switch_params_.started)
119  {
121  switch_params_.started = true;
122  }
123 
124  stopControllers(time);
125 
126  // start controllers once the switch is fully complete
128  {
129  startControllers(time);
130  }
131  // start controllers as soon as their required joints are done switching
132  else
133  {
134  startControllersAsap(time);
135  }
136 }
137 
139 {
140  // stop controllers
141  for (const auto& request : stop_request_)
142  {
143  if (request->isRunning())
144  {
145  request->stopRequest(time);
146  }
147  }
148 }
149 
151 {
152  // start controllers
154  {
155  for (const auto& request : start_request_)
156  {
157  request->startRequest(time);
158  }
159 
160  switch_params_.do_switch = false;
161  }
162  // abort controllers in case of error or timeout (if set)
164  (switch_params_.timeout > 0.0 &&
165  (time - switch_params_.init_time).toSec() > switch_params_.timeout))
166  {
167  for (const auto& request : start_request_)
168  {
169  request->abortRequest(time);
170  }
171 
172  switch_params_.do_switch = false;
173  }
174  // wait controllers
175  else
176  {
177  for (const auto& request : start_request_)
178  {
179  request->waitRequest(time);
180  }
181  }
182 }
183 
185 {
186  // start controllers if possible
187  for (const auto& request : start_request_)
188  {
189  if (!request->isRunning())
190  {
191  // find the info from this controller
192  for (const auto& controller : controllers_lists_[current_controllers_list_])
193  {
194  if (request == controller.c.get())
195  {
196  // ready to start
198  {
199  request->startRequest(time);
200  }
201  // abort on error or timeout (if set)
202  else if ((robot_hw_->switchResult(controller.info) == hardware_interface::RobotHW::ERROR) ||
203  (switch_params_.timeout > 0.0 &&
204  (time - switch_params_.init_time).toSec() > switch_params_.timeout))
205  {
206  request->abortRequest(time);
207  }
208  // controller is waiting
209  else
210  {
211  request->waitRequest(time);
212  }
213  }
214  continue;
215  }
216  }
217  }
218 
219  // all needed controllers started or aborted, switch done
220  if (std::all_of(start_request_.begin(), start_request_.end(),
222  return request->isRunning() || request->isAborted();
223  }))
224  {
225  switch_params_.do_switch = false;
226  }
227 }
228 
229 bool ControllerManager::loadController(const std::string& name)
230 {
231  ROS_DEBUG("Will load controller '%s'", name.c_str());
232 
233  // lock controllers
234  std::lock_guard<std::recursive_mutex> guard(controllers_lock_);
235 
236  // get reference to controller list
237  int free_controllers_list = (current_controllers_list_ + 1) % 2;
238  while (ros::ok() && free_controllers_list == used_by_realtime_)
239  {
240  if (!ros::ok())
241  {
242  return false;
243  }
244  std::this_thread::sleep_for(std::chrono::microseconds(200));
245  }
246  std::vector<ControllerSpec>
248  &to = controllers_lists_[free_controllers_list];
249  to.clear();
250 
251  // Copy all controllers from the 'from' list to the 'to' list
252  for (const auto& controller : from)
253  to.push_back(controller);
254 
255  // Checks that we're not duplicating controllers
256  for (const auto& controller : to)
257  {
258  if (controller.info.name == name)
259  {
260  to.clear();
261  ROS_ERROR("A controller named '%s' was already loaded inside the controller manager", name.c_str());
262  return false;
263  }
264  }
265 
266  ros::NodeHandle c_nh;
267  // Constructs the controller
268  try{
269  c_nh = ros::NodeHandle(root_nh_, name);
270  }
271  catch(std::exception &e) {
272  ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s':\n%s", name.c_str(), e.what());
273  return false;
274  }
275  catch(...){
276  ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s'", name.c_str());
277  return false;
278  }
280  std::string type;
281  if (c_nh.getParam("type", type))
282  {
283  ROS_DEBUG("Constructing controller '%s' of type '%s'", name.c_str(), type.c_str());
284  try
285  {
286  // Trying loading the controller using all of our controller loaders. Exit once we've found the first valid loaded controller
287  auto it = controller_loaders_.begin();
288  while (!c && it != controller_loaders_.end())
289  {
290  for (const auto& cur_type : (*it)->getDeclaredClasses()){
291  if (type == cur_type){
292  c = (*it)->createInstance(type);
293  }
294  }
295  ++it;
296  }
297  }
298  catch (const std::runtime_error &ex)
299  {
300  ROS_ERROR("Could not load class '%s': %s", type.c_str(), ex.what());
301  }
302  }
303  else
304  {
305  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());
306  to.clear();
307  return false;
308  }
309 
310  // checks if controller was constructed
311  if (!c)
312  {
313  ROS_ERROR("Could not load controller '%s' because controller type '%s' does not exist.", name.c_str(), type.c_str());
314  ROS_ERROR("Use 'rosservice call controller_manager/list_controller_types' to get the available types");
315  to.clear();
316  return false;
317  }
318 
319  // Initializes the controller
320  ROS_DEBUG("Initializing controller '%s'", name.c_str());
321  bool initialized;
322  controller_interface::ControllerBase::ClaimedResources claimed_resources; // Gets populated during initRequest call
323  try{
324  initialized = c->initRequest(robot_hw_, root_nh_, c_nh, claimed_resources);
325  }
326  catch(std::exception &e){
327  ROS_ERROR("Exception thrown while initializing controller '%s'.\n%s", name.c_str(), e.what());
328  initialized = false;
329  }
330  catch(...){
331  ROS_ERROR("Exception thrown while initializing controller '%s'", name.c_str());
332  initialized = false;
333  }
334  if (!initialized)
335  {
336  to.clear();
337  ROS_ERROR("Initializing controller '%s' failed", name.c_str());
338  return false;
339  }
340  ROS_DEBUG("Initialized controller '%s' successful", name.c_str());
341 
342  // Adds the controller to the new list
343  to.resize(to.size() + 1);
344  to.back().info.type = type;
345  to.back().info.name = name;
346  to.back().info.claimed_resources = claimed_resources;
347  to.back().c = c;
348 
349  // Destroys the old controllers list when the realtime thread is finished with it.
350  int former_current_controllers_list_ = current_controllers_list_;
351  current_controllers_list_ = free_controllers_list;
352  while (ros::ok() && used_by_realtime_ == former_current_controllers_list_)
353  {
354  if (!ros::ok())
355  {
356  return false;
357  }
358  std::this_thread::sleep_for(std::chrono::microseconds(200));
359  }
360  from.clear();
361 
362  ROS_DEBUG("Successfully load controller '%s'", name.c_str());
363  return true;
364 }
365 
366 
367 bool ControllerManager::unloadController(const std::string &name)
368 {
369  ROS_DEBUG("Will unload controller '%s'", name.c_str());
370 
371  // lock the controllers
372  std::lock_guard<std::recursive_mutex> guard(controllers_lock_);
373 
374  // get reference to controller list
375  int free_controllers_list = (current_controllers_list_ + 1) % 2;
376  while (ros::ok() && free_controllers_list == used_by_realtime_)
377  {
378  if (!ros::ok())
379  {
380  return false;
381  }
382  std::this_thread::sleep_for(std::chrono::microseconds(200));
383  }
384  std::vector<ControllerSpec>
386  &to = controllers_lists_[free_controllers_list];
387  to.clear();
388 
389  // Transfers the running controllers over, skipping the one to be removed and the running ones.
390  bool removed = false;
391  for (const auto& controller : from)
392  {
393  if (controller.info.name == name){
394  if (controller.c->isRunning()){
395  to.clear();
396  ROS_ERROR("Could not unload controller with name '%s' because it is still running",
397  name.c_str());
398  return false;
399  }
400  removed = true;
401  }
402  else
403  to.push_back(controller);
404  }
405 
406  // Fails if we could not remove the controllers
407  if (!removed)
408  {
409  to.clear();
410  ROS_ERROR("Could not unload controller with name '%s' because no controller with this name exists",
411  name.c_str());
412  return false;
413  }
414 
415  // Destroys the old controllers list when the realtime thread is finished with it.
416  ROS_DEBUG("Realtime switches over to new controller list");
417  int former_current_controllers_list_ = current_controllers_list_;
418  current_controllers_list_ = free_controllers_list;
419  while (ros::ok() && used_by_realtime_ == former_current_controllers_list_)
420  {
421  if (!ros::ok())
422  {
423  return false;
424  }
425  std::this_thread::sleep_for(std::chrono::microseconds(200));
426  }
427  ROS_DEBUG("Destruct controller");
428  from.clear();
429  ROS_DEBUG("Destruct controller finished");
430 
431  ROS_DEBUG("Successfully unloaded controller '%s'", name.c_str());
432  return true;
433 }
434 
435 
436 bool ControllerManager::switchController(const std::vector<std::string>& start_controllers,
437  const std::vector<std::string>& stop_controllers,
438  int strictness, bool start_asap, double timeout)
439 {
441 
442  if (!stop_request_.empty() || !start_request_.empty())
443  ROS_FATAL("The internal stop and start request lists are not empty at the beginning of the swithController() call. This should not happen.");
444 
445  if (strictness == 0){
446  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.",
447  controller_manager_msgs::SwitchController::Request::STRICT,
448  controller_manager_msgs::SwitchController::Request::BEST_EFFORT);
449  strictness = controller_manager_msgs::SwitchController::Request::BEST_EFFORT;
450  }
451 
452  ROS_DEBUG("switching controllers:");
453  for (const auto& controller : start_controllers)
454  ROS_DEBUG(" - starting controller '%s'", controller.c_str());
455  for (const auto& controller : stop_controllers)
456  ROS_DEBUG(" - stopping controller '%s'", controller.c_str());
457 
458  // lock controllers
459  std::lock_guard<std::recursive_mutex> guard(controllers_lock_);
460 
462  // list all controllers to stop
463  for (const auto& controller : stop_controllers)
464  {
465  ct = getControllerByName(controller);
466  if (ct == nullptr){
467  if (strictness == controller_manager_msgs::SwitchController::Request::STRICT){
468  ROS_ERROR("Could not stop controller with name '%s' because no controller with this name exists",
469  controller.c_str());
470  stop_request_.clear();
471  return false;
472  }
473  else{
474  ROS_DEBUG("Could not stop controller with name '%s' because no controller with this name exists",
475  controller.c_str());
476  }
477  }
478  else{
479  ROS_DEBUG("Found controller '%s' that needs to be stopped in list of controllers",
480  controller.c_str());
481  stop_request_.push_back(ct);
482  }
483  }
484  ROS_DEBUG("Stop request vector has size %i", (int)stop_request_.size());
485 
486  // list all controllers to start
487  for (const auto& controller : start_controllers)
488  {
489  ct = getControllerByName(controller);
490  if (ct == nullptr){
491  if (strictness == controller_manager_msgs::SwitchController::Request::STRICT){
492  ROS_ERROR("Could not start controller with name '%s' because no controller with this name exists",
493  controller.c_str());
494  stop_request_.clear();
495  start_request_.clear();
496  return false;
497  }
498  else{
499  ROS_DEBUG("Could not start controller with name '%s' because no controller with this name exists",
500  controller.c_str());
501  }
502  }
503  else{
504  ROS_DEBUG("Found controller '%s' that needs to be started in list of controllers",
505  controller.c_str());
506  start_request_.push_back(ct);
507  }
508  }
509  ROS_DEBUG("Start request vector has size %i", (int)start_request_.size());
510 
511  // Do the resource management checking
512  std::list<hardware_interface::ControllerInfo> info_list;
513  switch_start_list_.clear();
514  switch_stop_list_.clear();
515 
516  const auto &controllers = controllers_lists_[current_controllers_list_];
517  for (const auto& controller : controllers)
518  {
519  bool in_stop_list = false;
520  for (const auto& request : stop_request_)
521  {
522  if (request == controller.c.get())
523  {
524  in_stop_list = true;
525  break;
526  }
527  }
528 
529  bool in_start_list = false;
530  for (const auto& request : start_request_)
531  {
532  if (request == controller.c.get())
533  {
534  in_start_list = true;
535  break;
536  }
537  }
538 
539  const bool is_running = controller.c->isRunning();
540  const hardware_interface::ControllerInfo &info = controller.info;
541 
542  if(!is_running && in_stop_list){ // check for double stop
543  if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){
544  ROS_ERROR_STREAM("Could not stop controller '" << info.name << "' since it is not running");
545  stop_request_.clear();
546  start_request_.clear();
547  return false;
548  } else {
549  in_stop_list = false;
550  }
551  }
552 
553  if(is_running && !in_stop_list && in_start_list){ // check for doubled start
554  if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){
555  ROS_ERROR_STREAM("Controller '" << info.name << "' is already running");
556  stop_request_.clear();
557  start_request_.clear();
558  return false;
559  } else {
560  in_start_list = false;
561  }
562  }
563 
564  if(is_running && in_stop_list && !in_start_list){ // running and real stop
565  switch_stop_list_.push_back(info);
566  }
567  else if(!is_running && !in_stop_list && in_start_list){ // start, but no restart
568  switch_start_list_.push_back(info);
569  }
570 
571  bool add_to_list = is_running;
572  if (in_stop_list)
573  add_to_list = false;
574  if (in_start_list)
575  add_to_list = true;
576 
577  if (add_to_list)
578  info_list.push_back(info);
579  }
580 
581  bool in_conflict = robot_hw_->checkForConflict(info_list);
582  if (in_conflict)
583  {
584  ROS_ERROR("Could not switch controllers, due to resource conflict");
585  stop_request_.clear();
586  start_request_.clear();
587  return false;
588  }
589 
591  {
592  ROS_ERROR("Could not switch controllers. The hardware interface combination for the requested controllers is unfeasible.");
593  stop_request_.clear();
594  start_request_.clear();
595  return false;
596  }
597 
598  // start the atomic controller switching
599  switch_params_.strictness = strictness;
600  switch_params_.start_asap = start_asap;
602  switch_params_.timeout = timeout;
603  switch_params_.do_switch = true;
604 
605  // wait until switch is finished
606  ROS_DEBUG("Request atomic controller switch from realtime loop");
607  auto start_time = std::chrono::system_clock::now();
608  bool timed_out = false;
609  while (ros::ok() && switch_params_.do_switch)
610  {
611  if (!ros::ok())
612  {
613  return false;
614  }
615  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start_time;
616  if (diff.count() < timeout+1.0 || timeout == 0){
617  std::this_thread::sleep_for(std::chrono::microseconds(100));
618  } else {
619  ROS_DEBUG("Timed out while switching controllers. Exiting...");
620  timed_out = true;
621  break;
622  }
623  }
624  start_request_.clear();
625  stop_request_.clear();
626  if(timed_out){
627  ROS_DEBUG("Exited wait until switch is finished loop using non-ROS-time timeout");
628  return false;
629  }
630  ROS_DEBUG("Successfully switched controllers");
631  return true;
632 }
633 
634 
636  controller_manager_msgs::ReloadControllerLibraries::Request &req,
637  controller_manager_msgs::ReloadControllerLibraries::Response &resp)
638 {
639  // lock services
640  ROS_DEBUG("reload libraries service called");
641  std::lock_guard<std::mutex> guard(services_lock_);
642  ROS_DEBUG("reload libraries service locked");
643 
644  // only reload libraries if no controllers are running
645  std::vector<std::string> controllers;
646  getControllerNames(controllers);
647  if (!controllers.empty() && !req.force_kill){
648  ROS_ERROR("Controller manager: Cannot reload controller libraries because there are still %i controllers running", (int)controllers.size());
649  resp.ok = false;
650  return true;
651  }
652 
653  // kill running controllers if requested
654  if (!controllers.empty()){
655  ROS_INFO("Controller manager: Killing all running controllers");
656  std::vector<std::string> empty;
657  if (!switchController(empty,controllers, controller_manager_msgs::SwitchController::Request::BEST_EFFORT)){
658  ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to stop running controllers");
659  resp.ok = false;
660  return true;
661  }
662  for (const auto& controller : controllers){
663  if (!unloadController(controller)){
664  ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to unload controller '%s'",
665  controller.c_str());
666  resp.ok = false;
667  return true;
668  }
669  }
670  getControllerNames(controllers);
671  }
672  assert(controllers.empty());
673 
674  // Force a reload on all the PluginLoaders (internally, this recreates the plugin loaders)
675  for (const auto& controller_loader : controller_loaders_)
676  {
677  controller_loader->reload();
678  ROS_INFO("Controller manager: reloaded controller libraries for '%s'", controller_loader->getName().c_str());
679  }
680 
681  resp.ok = true;
682 
683  ROS_DEBUG("reload libraries service finished");
684  return true;
685 }
686 
687 
689  controller_manager_msgs::ListControllerTypes::Request &req,
690  controller_manager_msgs::ListControllerTypes::Response &resp)
691 {
692  // pretend to use the request
693  (void) req;
694 
695  // lock services
696  ROS_DEBUG("list types service called");
697  std::lock_guard<std::mutex> guard(services_lock_);
698  ROS_DEBUG("list types service locked");
699 
700  for (const auto& controller_loader : controller_loaders_)
701  {
702  std::vector<std::string> cur_types = controller_loader->getDeclaredClasses();
703  for (const auto& cur_type : cur_types)
704  {
705  resp.types.push_back(cur_type);
706  resp.base_classes.push_back(controller_loader->getName());
707  }
708  }
709 
710  ROS_DEBUG("list types service finished");
711  return true;
712 }
713 
714 
716  controller_manager_msgs::ListControllers::Request &req,
717  controller_manager_msgs::ListControllers::Response &resp)
718 {
719  // pretend to use the request
720  (void) req;
721 
722  // lock services
723  ROS_DEBUG("list controller service called");
724  std::lock_guard<std::mutex> services_guard(services_lock_);
725  ROS_DEBUG("list controller service locked");
726 
727  // lock controllers to get all names/types/states
728  std::lock_guard<std::recursive_mutex> controller_guard(controllers_lock_);
729  std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
730  resp.controller.resize(controllers.size());
731 
732  for (size_t i = 0; i < controllers.size(); ++i)
733  {
734  controller_manager_msgs::ControllerState& cs = resp.controller[i];
735  cs.name = controllers[i].info.name;
736  cs.type = controllers[i].info.type;
737 
738  cs.claimed_resources.clear();
739  typedef std::vector<hardware_interface::InterfaceResources> ClaimedResVec;
740  typedef ClaimedResVec::const_iterator ClaimedResIt;
741  const ClaimedResVec& c_resources = controllers[i].info.claimed_resources;
742  for (const auto& c_resource : c_resources)
743  {
744  controller_manager_msgs::HardwareInterfaceResources iface_res;
745  iface_res.hardware_interface = c_resource.hardware_interface;
746  std::copy(c_resource.resources.begin(), c_resource.resources.end(), std::back_inserter(iface_res.resources));
747  cs.claimed_resources.push_back(iface_res);
748  }
749 
750  if (controllers[i].c->isInitialized())
751  {
752  cs.state = "initialized";
753  }
754  else if (controllers[i].c->isRunning())
755  {
756  cs.state = "running";
757  }
758  else if (controllers[i].c->isStopped())
759  {
760  cs.state = "stopped";
761  }
762  else if (controllers[i].c->isWaiting())
763  {
764  cs.state = "waiting";
765  }
766  else if (controllers[i].c->isAborted())
767  {
768  cs.state = "aborted";
769  }
770  else
771  {
772  // should never happen
773  cs.state = "unknown";
774  }
775  }
776 
777  ROS_DEBUG("list controller service finished");
778  return true;
779 }
780 
781 
783  controller_manager_msgs::LoadController::Request &req,
784  controller_manager_msgs::LoadController::Response &resp)
785 {
786  // lock services
787  ROS_DEBUG("loading service called for controller '%s' ",req.name.c_str());
788  std::lock_guard<std::mutex> guard(services_lock_);
789  ROS_DEBUG("loading service locked");
790 
791  resp.ok = loadController(req.name);
792 
793  ROS_DEBUG("loading service finished for controller '%s' ",req.name.c_str());
794  return true;
795 }
796 
797 
799  controller_manager_msgs::UnloadController::Request &req,
800  controller_manager_msgs::UnloadController::Response &resp)
801 {
802  // lock services
803  ROS_DEBUG("unloading service called for controller '%s' ",req.name.c_str());
804  std::lock_guard<std::mutex> guard(services_lock_);
805  ROS_DEBUG("unloading service locked");
806 
807  resp.ok = unloadController(req.name);
808 
809  ROS_DEBUG("unloading service finished for controller '%s' ",req.name.c_str());
810  return true;
811 }
812 
813 
815  controller_manager_msgs::SwitchController::Request &req,
816  controller_manager_msgs::SwitchController::Response &resp)
817 {
818  // lock services
819  ROS_DEBUG("switching service called");
820  std::lock_guard<std::mutex> guard(services_lock_);
821  ROS_DEBUG("switching service locked");
822 
823  resp.ok = switchController(req.start_controllers, req.stop_controllers, req.strictness,
824  req.start_asap, req.timeout);
825 
826  ROS_DEBUG("switching service finished");
827  return true;
828 }
829 
831 {
832  controller_loaders_.push_back(controller_loader);
833 }
834 
835 }
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(...)
std::shared_ptr< ControllerBase > ControllerBaseSharedPtr
virtual void doSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
void startControllersAsap(const ros::Time &time)
bool loadController(const std::string &name)
Load a new controller by name.
void stopControllers(const ros::Time &time)
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)
void manageSwitch(const ros::Time &time)
hardware_interface::RobotHW * robot_hw_
#define ROS_WARN(...)
std::vector< controller_interface::ControllerBase * > start_request_
virtual bool checkForConflict(const std::list< ControllerInfo > &info) const
bool listControllerTypesSrv(controller_manager_msgs::ListControllerTypes::Request &req, controller_manager_msgs::ListControllerTypes::Response &resp)
bool switchController(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers, const int strictness, bool start_asap=WAIT_FOR_ALL_RESOURCES, double timeout=INFINITE_TIMEOUT)
Switch multiple controllers simultaneously.
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(...)
bool getParam(const std::string &key, std::string &s) const
ROSCPP_DECL bool ok()
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)
std::shared_ptr< ControllerLoaderInterface > ControllerLoaderInterfaceSharedPtr
virtual bool prepareSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
std::list< ControllerLoaderInterfaceSharedPtr > controller_loaders_
std::list< hardware_interface::ControllerInfo > switch_start_list_
const std::string & getNamespace() const
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)
void startControllers(const ros::Time &time)
static Time now()
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.
virtual SwitchState switchResult() const
std::recursive_mutex controllers_lock_
Mutex protecting the current controllers list.
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


controller_manager
Author(s): Wim Meeussen, Mathias Lüdtke
autogenerated on Mon Feb 28 2022 23:30:17