Go to the documentation of this file.
44 #include <controller_manager_msgs/LoadController.h>
48 class ControllerManager
55 if (!nh.
hasParam(
"controllers_list"))
57 ROS_INFO(
"Waiting for load_controller service...");
61 if (nh_list.getParam(
"state_controllers", controllers))
62 for (
int i = 0; i < controllers.
size(); ++i)
67 if (nh_list.getParam(
"main_controllers", controllers))
68 for (
int i = 0; i < controllers.
size(); ++i)
73 if (nh_list.getParam(
"calibration_controllers", controllers))
74 for (
int i = 0; i < controllers.
size(); ++i)
96 controller_manager_msgs::LoadController load_controller;
97 load_controller.request.name = 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());
124 for (
const auto& controller : controllers)
129 for (
const auto& controller : controllers)
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
std::vector< std::string > start_buffer_
void startController(const std::string &controller)
std::vector< std::string > main_controllers_
void stopCalibrationControllers()
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
void loadController(const std::string &controller)
void stopMainControllers()
void stopController(const std::string &controller)
void stopControllers(const std::vector< std::string > &controllers)
void startMainControllers()
ros::ServiceClient load_client_
SwitchControllersServiceCaller switch_caller_
ControllerManager(ros::NodeHandle &nh)
bool hasParam(const std::string &key) const
void startControllers(const std::vector< std::string > &controllers)
std::vector< std::string > state_controllers_
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
std::vector< std::string > stop_buffer_
void startStateControllers()
void startCalibrationControllers()
std::vector< std::string > calibration_controllers_
rm_common
Author(s):
autogenerated on Sun Apr 6 2025 02:22:01