33 #include <boost/thread/thread.hpp> 34 #include <boost/thread/condition.hpp> 38 #include <controller_manager_msgs/ControllerState.h> 46 cm_node_(nh,
"controller_manager"),
49 please_switch_(false),
50 current_controllers_list_(0),
56 "controller_interface::ControllerBase") ) );
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);
92 for (
size_t i=0; i<controllers.size(); i++)
93 controllers[i].c->updateRequest(time, period);
104 ROS_FATAL(
"Failed to stop controller in realtime loop. This should never happen.");
109 ROS_FATAL(
"Failed to start controller in realtime loop. This should never happen.");
121 for (
size_t i = 0; i < controllers.size(); ++i)
123 if (controllers[i].info.name == name)
124 return controllers[i].c.get();
134 for (
size_t i = 0; i < controllers.size(); ++i)
136 names.push_back(controllers[i].info.name);
143 ROS_DEBUG(
"Will load controller '%s'", name.c_str());
155 std::vector<ControllerSpec>
161 for (
size_t i = 0; i < from.size(); ++i)
162 to.push_back(from[i]);
165 for (
size_t j = 0; j < to.size(); ++j)
167 if (to[j].info.name == name)
170 ROS_ERROR(
"A controller named '%s' was already loaded inside the controller manager", name.c_str());
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());
185 ROS_ERROR(
"Exception thrown while constructing nodehandle for controller with name '%s'", name.c_str());
192 ROS_DEBUG(
"Constructing controller '%s' of type '%s'", name.c_str(), type.c_str());
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);
208 catch (
const std::runtime_error &ex)
210 ROS_ERROR(
"Could not load class %s: %s", type.c_str(), ex.what());
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());
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");
230 ROS_DEBUG(
"Initializing controller '%s'", name.c_str());
236 catch(std::exception &e){
237 ROS_ERROR(
"Exception thrown while initializing controller %s.\n%s", name.c_str(), e.what());
241 ROS_ERROR(
"Exception thrown while initializing controller %s", name.c_str());
247 ROS_ERROR(
"Initializing controller '%s' failed", name.c_str());
250 ROS_DEBUG(
"Initialized controller '%s' successful", name.c_str());
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;
269 ROS_DEBUG(
"Successfully load controller '%s'", name.c_str());
278 ROS_DEBUG(
"Will unload controller '%s'", name.c_str());
290 std::vector<ControllerSpec>
296 bool removed =
false;
297 for (
size_t i = 0; i < from.size(); ++i)
299 if (from[i].info.name == name){
300 if (from[i].c->isRunning()){
302 ROS_ERROR(
"Could not unload controller with name %s because it is still running",
309 to.push_back(from[i]);
316 ROS_ERROR(
"Could not unload controller with name %s because no controller with this name exists",
322 ROS_DEBUG(
"Realtime switches over to new controller list");
332 ROS_DEBUG(
"Destruct controller finished");
334 ROS_DEBUG(
"Successfully unloaded controller '%s'", name.c_str());
341 const std::vector<std::string>& stop_controllers,
345 ROS_FATAL(
"The internal stop and start request lists are not empty at the beginning of the swithController() call. This should not happen.");
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;
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());
365 for (
unsigned int i=0; i<stop_controllers.size(); i++)
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());
376 ROS_DEBUG(
"Could not stop controller with name %s because no controller with this name exists",
377 stop_controllers[i].c_str());
381 ROS_DEBUG(
"Found controller %s that needs to be stopped in list of controllers",
382 stop_controllers[i].c_str());
389 for (
unsigned int i=0; i<start_controllers.size(); i++)
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());
401 ROS_DEBUG(
"Could not start controller with name %s because no controller with this name exists",
402 start_controllers[i].c_str());
406 ROS_DEBUG(
"Found controller %s that needs to be started in list of controllers",
407 start_controllers[i].c_str());
414 std::list<hardware_interface::ControllerInfo> info_list;
419 for (
size_t i = 0; i < controllers.size(); ++i)
421 bool in_stop_list =
false;
431 bool in_start_list =
false;
436 in_start_list =
true;
441 const bool is_running = controllers[i].c->isRunning();
444 if(!is_running && in_stop_list){
445 if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){
451 in_stop_list =
false;
455 if(is_running && !in_stop_list && in_start_list){
456 if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){
462 in_start_list =
false;
466 if(is_running && in_stop_list && !in_start_list){
469 else if(!is_running && !in_stop_list && in_start_list){
473 bool add_to_list = is_running;
480 info_list.push_back(info);
486 ROS_ERROR(
"Could not switch controllers, due to resource conflict");
494 ROS_ERROR(
"Could not switch controllers. The hardware interface combination for the requested controllers is unfeasible.");
505 ROS_DEBUG(
"Request atomic controller switch from realtime loop");
514 ROS_DEBUG(
"Successfully switched controllers");
523 controller_manager_msgs::ReloadControllerLibraries::Request &req,
524 controller_manager_msgs::ReloadControllerLibraries::Response &resp)
527 ROS_DEBUG(
"reload libraries service called");
529 ROS_DEBUG(
"reload libraries service locked");
532 std::vector<std::string> 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());
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");
549 for (
unsigned int i=0; i<controllers.size(); i++){
551 ROS_ERROR(
"Controller manager: Cannot reload controller libraries because failed to unload controller %s",
552 controllers[i].c_str());
559 assert(controllers.empty());
565 ROS_INFO(
"Controller manager: reloaded controller libraries for %s", (*it)->getName().c_str());
570 ROS_DEBUG(
"reload libraries service finished");
576 controller_manager_msgs::ListControllerTypes::Request &req,
577 controller_manager_msgs::ListControllerTypes::Response &resp)
589 std::vector<std::string> cur_types = (*it)->getDeclaredClasses();
590 for(
size_t i=0; i < cur_types.size(); i++)
592 resp.types.push_back(cur_types[i]);
593 resp.base_classes.push_back((*it)->getName());
597 ROS_DEBUG(
"list types service finished");
603 controller_manager_msgs::ListControllers::Request &req,
604 controller_manager_msgs::ListControllers::Response &resp)
610 ROS_DEBUG(
"list controller service called");
612 ROS_DEBUG(
"list controller service locked");
617 resp.controller.resize(controllers.size());
619 for (
size_t i = 0; i < controllers.size(); ++i)
621 controller_manager_msgs::ControllerState& cs = resp.controller[i];
622 cs.name = controllers[i].info.name;
623 cs.type = controllers[i].info.type;
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)
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);
637 if (controllers[i].c->isRunning())
638 cs.state =
"running";
640 cs.state =
"stopped";
643 ROS_DEBUG(
"list controller service finished");
649 controller_manager_msgs::LoadController::Request &req,
650 controller_manager_msgs::LoadController::Response &resp)
653 ROS_DEBUG(
"loading service called for controller %s ",req.name.c_str());
659 ROS_DEBUG(
"loading service finished for controller %s ",req.name.c_str());
665 controller_manager_msgs::UnloadController::Request &req,
666 controller_manager_msgs::UnloadController::Response &resp)
669 ROS_DEBUG(
"unloading service called for controller %s ",req.name.c_str());
675 ROS_DEBUG(
"unloading service finished for controller %s ",req.name.c_str());
681 controller_manager_msgs::SwitchController::Request &req,
682 controller_manager_msgs::SwitchController::Response &resp)
689 resp.ok =
switchController(req.start_controllers, req.stop_controllers, req.strictness);
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_
virtual void doSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
ros::ServiceServer srv_switch_controller_
bool loadController(const std::string &name)
Load a new controller by name.
boost::mutex services_lock_
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.
ros::ServiceServer srv_load_controller_
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)
ros::ServiceServer srv_reload_libraries_
hardware_interface::RobotHW * robot_hw_
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.
ros::ServiceServer srv_list_controllers_
virtual ~ControllerManager()
bool unloadController(const std::string &name)
Unload a controller by name.
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.
ros::ServiceServer srv_unload_controller_
boost::shared_ptr< ControllerLoaderInterface > ControllerLoaderInterfaceSharedPtr
ros::ServiceServer srv_list_controller_types_
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.