controller_manager.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by astro on 2021/5/15.
36 //
37 #pragma once
38 
40 
41 #include <algorithm>
42 
43 #include <ros/ros.h>
44 #include <controller_manager_msgs/LoadController.h>
45 
46 namespace rm_common
47 {
48 class ControllerManager
49 {
50 public:
52  : load_client_(nh.serviceClient<controller_manager_msgs::LoadController>("/controller_manager/load_controller"))
53  , switch_caller_(nh)
54  {
55  if (!nh.hasParam("controllers_list"))
56  ROS_ERROR("No controllers defined");
57  ROS_INFO("Waiting for load_controller service...");
59  ros::NodeHandle nh_list(nh, "controllers_list");
60  XmlRpc::XmlRpcValue controllers;
61  if (nh_list.getParam("state_controllers", controllers))
62  for (int i = 0; i < controllers.size(); ++i)
63  {
64  state_controllers_.push_back(controllers[i]);
65  loadController(controllers[i]);
66  }
67  if (nh_list.getParam("main_controllers", controllers))
68  for (int i = 0; i < controllers.size(); ++i)
69  {
70  main_controllers_.push_back(controllers[i]);
71  loadController(controllers[i]);
72  }
73  if (nh_list.getParam("calibration_controllers", controllers))
74  for (int i = 0; i < controllers.size(); ++i)
75  {
76  calibration_controllers_.push_back(controllers[i]);
77  loadController(controllers[i]);
78  }
79  }
80  void update()
81  {
83  {
86  if (!start_buffer_.empty() || !stop_buffer_.empty())
87  {
89  start_buffer_.clear();
90  stop_buffer_.clear();
91  }
92  }
93  }
94  void loadController(const std::string& controller)
95  {
96  controller_manager_msgs::LoadController load_controller;
97  load_controller.request.name = controller;
98  load_client_.call(load_controller);
99  if (load_controller.response.ok)
100  ROS_INFO("Loaded %s", controller.c_str());
101  else
102  ROS_ERROR("Fail to load %s", controller.c_str());
103  }
104  void startController(const std::string& controller)
105  {
106  if (std::find(start_buffer_.begin(), start_buffer_.end(), controller) == start_buffer_.end())
107  start_buffer_.push_back(controller);
108  // AVoid setting controller to start and stop in the same time
109  auto item = std::find(stop_buffer_.begin(), stop_buffer_.end(), controller);
110  if (item != stop_buffer_.end())
111  stop_buffer_.erase(item);
112  }
113  void stopController(const std::string& controller)
114  {
115  if (std::find(stop_buffer_.begin(), stop_buffer_.end(), controller) == stop_buffer_.end())
116  stop_buffer_.push_back(controller);
117  // AVoid setting controller to start and stop in the same time
118  auto item = std::find(start_buffer_.begin(), start_buffer_.end(), controller);
119  if (item != start_buffer_.end())
120  start_buffer_.erase(item);
121  }
122  void startControllers(const std::vector<std::string>& controllers)
123  {
124  for (const auto& controller : controllers)
125  startController(controller);
126  }
127  void stopControllers(const std::vector<std::string>& controllers)
128  {
129  for (const auto& controller : controllers)
130  stopController(controller);
131  }
132  void startStateControllers()
133  {
135  }
136  void startMainControllers()
137  {
139  }
140  void stopMainControllers()
141  {
143  }
145  {
147  }
149  {
151  }
152  bool isCalling()
153  {
154  return switch_caller_.isCalling();
155  }
156 
157 private:
160  std::vector<std::string> start_buffer_, stop_buffer_;
162 };
163 
164 } // namespace rm_common
XmlRpc::XmlRpcValue::size
int size() const
rm_common::SwitchControllersServiceCaller::stopControllers
void stopControllers(const std::vector< std::string > &controllers)
Definition: service_caller.h:180
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
rm_common::ControllerManager::start_buffer_
std::vector< std::string > start_buffer_
Definition: controller_manager.h:222
rm_common::ControllerManager::startController
void startController(const std::string &controller)
Definition: controller_manager.h:166
rm_common::ControllerManager::main_controllers_
std::vector< std::string > main_controllers_
Definition: controller_manager.h:221
rm_common::ControllerManager::stopCalibrationControllers
void stopCalibrationControllers()
Definition: controller_manager.h:210
ros.h
serviceClient
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
rm_common::ControllerManager::loadController
void loadController(const std::string &controller)
Definition: controller_manager.h:156
rm_common::ControllerManager::stopMainControllers
void stopMainControllers()
Definition: controller_manager.h:202
rm_common::ControllerManager::stopController
void stopController(const std::string &controller)
Definition: controller_manager.h:175
rm_common::ControllerManager::update
void update()
Definition: controller_manager.h:142
service_caller.h
rm_common::ControllerManager::stopControllers
void stopControllers(const std::vector< std::string > &controllers)
Definition: controller_manager.h:189
rm_common::ControllerManager::startMainControllers
void startMainControllers()
Definition: controller_manager.h:198
rm_common::ControllerManager::load_client_
ros::ServiceClient load_client_
Definition: controller_manager.h:220
rm_common::ServiceCallerBase::isCalling
bool isCalling()
Definition: service_caller.h:164
rm_common::ControllerManager::switch_caller_
SwitchControllersServiceCaller switch_caller_
Definition: controller_manager.h:223
rm_common::ControllerManager::ControllerManager
ControllerManager(ros::NodeHandle &nh)
Definition: controller_manager.h:113
rm_common
Definition: calibration_queue.h:43
ros::ServiceClient
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
rm_common::ControllerManager::startControllers
void startControllers(const std::vector< std::string > &controllers)
Definition: controller_manager.h:184
rm_common::SwitchControllersServiceCaller::startControllers
void startControllers(const std::vector< std::string > &controllers)
Definition: service_caller.h:176
rm_common::ControllerManager::isCalling
bool isCalling()
Definition: controller_manager.h:214
rm_common::ControllerManager::state_controllers_
std::vector< std::string > state_controllers_
Definition: controller_manager.h:221
ROS_ERROR
#define ROS_ERROR(...)
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
rm_common::ControllerManager::stop_buffer_
std::vector< std::string > stop_buffer_
Definition: controller_manager.h:222
rm_common::SwitchControllersServiceCaller
Definition: service_caller.h:167
ROS_INFO
#define ROS_INFO(...)
rm_common::ControllerManager::startStateControllers
void startStateControllers()
Definition: controller_manager.h:194
rm_common::ControllerManager::startCalibrationControllers
void startCalibrationControllers()
Definition: controller_manager.h:206
rm_common::ServiceCallerBase::callService
void callService()
Definition: service_caller.h:153
XmlRpc::XmlRpcValue
ros::NodeHandle
rm_common::ControllerManager::calibration_controllers_
std::vector< std::string > calibration_controllers_
Definition: controller_manager.h:221


rm_common
Author(s):
autogenerated on Sun Apr 6 2025 02:22:01