44#include <controller_manager_msgs/LoadController.h>
52 : load_client_(nh.serviceClient<controller_manager_msgs::LoadController>(
"/controller_manager/load_controller"))
55 if (!nh.hasParam(
"controllers_list"))
56 ROS_ERROR(
"No controllers defined");
57 ROS_INFO(
"Waiting for load_controller service...");
58 load_client_.waitForExistence();
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)
64 state_controllers_.push_back(controllers[i]);
67 if (nh_list.getParam(
"main_controllers", controllers))
68 for (
int i = 0; i < controllers.size(); ++i)
70 main_controllers_.push_back(controllers[i]);
73 if (nh_list.getParam(
"calibration_controllers", controllers))
74 for (
int i = 0; i < controllers.size(); ++i)
76 calibration_controllers_.push_back(controllers[i]);
86 if (!start_buffer_.empty() || !stop_buffer_.empty())
89 start_buffer_.clear();
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());
102 ROS_ERROR(
"Fail to load %s", controller.c_str());
106 if (std::find(start_buffer_.begin(), start_buffer_.end(), controller) == start_buffer_.end())
107 start_buffer_.push_back(controller);
109 auto item = std::find(stop_buffer_.begin(), stop_buffer_.end(), controller);
110 if (item != stop_buffer_.end())
111 stop_buffer_.erase(item);
115 if (std::find(stop_buffer_.begin(), stop_buffer_.end(), controller) == stop_buffer_.end())
116 stop_buffer_.push_back(controller);
118 auto item = std::find(start_buffer_.begin(), start_buffer_.end(), controller);
119 if (item != start_buffer_.end())
120 start_buffer_.erase(item);
124 for (
const auto& controller : controllers)
129 for (
const auto& controller : controllers)
158 ros::ServiceClient load_client_;
159 std::vector<std::string> state_controllers_, main_controllers_, calibration_controllers_;
160 std::vector<std::string> start_buffer_, stop_buffer_;
Definition controller_manager.h:49
void stopCalibrationControllers()
Definition controller_manager.h:148
void loadController(const std::string &controller)
Definition controller_manager.h:94
void stopMainControllers()
Definition controller_manager.h:140
void startCalibrationControllers()
Definition controller_manager.h:144
ControllerManager(ros::NodeHandle &nh)
Definition controller_manager.h:51
void startController(const std::string &controller)
Definition controller_manager.h:104
void update()
Definition controller_manager.h:80
void startStateControllers()
Definition controller_manager.h:132
bool isCalling()
Definition controller_manager.h:152
void startControllers(const std::vector< std::string > &controllers)
Definition controller_manager.h:122
void startMainControllers()
Definition controller_manager.h:136
void stopController(const std::string &controller)
Definition controller_manager.h:113
void stopControllers(const std::vector< std::string > &controllers)
Definition controller_manager.h:127
bool isCalling()
Definition service_caller.h:102
void callService()
Definition service_caller.h:91
Definition service_caller.h:137
void startControllers(const std::vector< std::string > &controllers)
Definition service_caller.h:145
void stopControllers(const std::vector< std::string > &controllers)
Definition service_caller.h:149
Definition calibration_queue.h:44