39 #include <controller_manager_msgs/ControllerState.h> 48 cm_node_(nh,
"controller_manager")
53 "controller_interface::ControllerBase") ) );
71 if (reset_controllers){
73 if (controller.c->isRunning()){
74 controller.c->stopRequest(time);
75 controller.c->startRequest(time);
83 controller.c->updateRequest(time, period);
99 if (controller.info.name == name)
100 return controller.c.get();
111 names.push_back(controller.info.name);
143 if (request->isRunning())
145 request->stopRequest(time);
157 request->startRequest(time);
169 request->abortRequest(time);
179 request->waitRequest(time);
189 if (!request->isRunning())
194 if (request == controller.c.get())
199 request->startRequest(time);
206 request->abortRequest(time);
211 request->waitRequest(time);
220 if (std::all_of(start_request_.begin(), start_request_.end(),
222 return request->isRunning() || request->isAborted();
231 ROS_DEBUG(
"Will load controller '%s'", name.c_str());
244 std::this_thread::sleep_for(std::chrono::microseconds(200));
246 std::vector<ControllerSpec>
252 for (
const auto& controller : from)
253 to.push_back(controller);
256 for (
const auto& controller : to)
258 if (controller.info.name == name)
261 ROS_ERROR(
"A controller named '%s' was already loaded inside the controller manager", name.c_str());
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());
276 ROS_ERROR(
"Exception thrown while constructing nodehandle for controller with name '%s'", name.c_str());
283 ROS_DEBUG(
"Constructing controller '%s' of type '%s'", name.c_str(), type.c_str());
290 for (
const auto& cur_type : (*it)->getDeclaredClasses()){
291 if (type == cur_type){
292 c = (*it)->createInstance(type);
298 catch (
const std::runtime_error &ex)
300 ROS_ERROR(
"Could not load class '%s': %s", type.c_str(), ex.what());
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());
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");
320 ROS_DEBUG(
"Initializing controller '%s'", name.c_str());
326 catch(std::exception &e){
327 ROS_ERROR(
"Exception thrown while initializing controller '%s'.\n%s", name.c_str(), e.what());
331 ROS_ERROR(
"Exception thrown while initializing controller '%s'", name.c_str());
337 ROS_ERROR(
"Initializing controller '%s' failed", name.c_str());
340 ROS_DEBUG(
"Initialized controller '%s' successful", name.c_str());
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;
358 std::this_thread::sleep_for(std::chrono::microseconds(200));
362 ROS_DEBUG(
"Successfully load controller '%s'", name.c_str());
369 ROS_DEBUG(
"Will unload controller '%s'", name.c_str());
382 std::this_thread::sleep_for(std::chrono::microseconds(200));
384 std::vector<ControllerSpec>
390 bool removed =
false;
391 for (
const auto& controller : from)
393 if (controller.info.name == name){
394 if (controller.c->isRunning()){
396 ROS_ERROR(
"Could not unload controller with name '%s' because it is still running",
403 to.push_back(controller);
410 ROS_ERROR(
"Could not unload controller with name '%s' because no controller with this name exists",
416 ROS_DEBUG(
"Realtime switches over to new controller list");
425 std::this_thread::sleep_for(std::chrono::microseconds(200));
429 ROS_DEBUG(
"Destruct controller finished");
431 ROS_DEBUG(
"Successfully unloaded controller '%s'", name.c_str());
437 const std::vector<std::string>& stop_controllers,
438 int strictness,
bool start_asap,
double timeout)
443 ROS_FATAL(
"The internal stop and start request lists are not empty at the beginning of the swithController() call. This should not happen.");
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;
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());
463 for (
const auto& controller : stop_controllers)
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",
474 ROS_DEBUG(
"Could not stop controller with name '%s' because no controller with this name exists",
479 ROS_DEBUG(
"Found controller '%s' that needs to be stopped in list of controllers",
487 for (
const auto& controller : start_controllers)
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",
499 ROS_DEBUG(
"Could not start controller with name '%s' because no controller with this name exists",
504 ROS_DEBUG(
"Found controller '%s' that needs to be started in list of controllers",
512 std::list<hardware_interface::ControllerInfo> info_list;
517 for (
const auto& controller : controllers)
519 bool in_stop_list =
false;
522 if (request == controller.c.get())
529 bool in_start_list =
false;
532 if (request == controller.c.get())
534 in_start_list =
true;
539 const bool is_running = controller.c->isRunning();
542 if(!is_running && in_stop_list){
543 if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){
545 stop_request_.clear();
546 start_request_.clear();
549 in_stop_list =
false;
553 if(is_running && !in_stop_list && in_start_list){
554 if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){
556 stop_request_.clear();
557 start_request_.clear();
560 in_start_list =
false;
564 if(is_running && in_stop_list && !in_start_list){
567 else if(!is_running && !in_stop_list && in_start_list){
571 bool add_to_list = is_running;
578 info_list.push_back(info);
584 ROS_ERROR(
"Could not switch controllers, due to resource conflict");
592 ROS_ERROR(
"Could not switch controllers. The hardware interface combination for the requested controllers is unfeasible.");
606 ROS_DEBUG(
"Request atomic controller switch from realtime loop");
607 auto start_time = std::chrono::system_clock::now();
608 bool timed_out =
false;
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));
619 ROS_DEBUG(
"Timed out while switching controllers. Exiting...");
627 ROS_DEBUG(
"Exited wait until switch is finished loop using non-ROS-time timeout");
630 ROS_DEBUG(
"Successfully switched controllers");
636 controller_manager_msgs::ReloadControllerLibraries::Request &req,
637 controller_manager_msgs::ReloadControllerLibraries::Response &resp)
640 ROS_DEBUG(
"reload libraries service called");
642 ROS_DEBUG(
"reload libraries service locked");
645 std::vector<std::string> 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());
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");
662 for (
const auto& controller : controllers){
664 ROS_ERROR(
"Controller manager: Cannot reload controller libraries because failed to unload controller '%s'",
672 assert(controllers.empty());
677 controller_loader->reload();
678 ROS_INFO(
"Controller manager: reloaded controller libraries for '%s'", controller_loader->getName().c_str());
683 ROS_DEBUG(
"reload libraries service finished");
689 controller_manager_msgs::ListControllerTypes::Request &req,
690 controller_manager_msgs::ListControllerTypes::Response &resp)
702 std::vector<std::string> cur_types = controller_loader->getDeclaredClasses();
703 for (
const auto& cur_type : cur_types)
705 resp.types.push_back(cur_type);
706 resp.base_classes.push_back(controller_loader->getName());
710 ROS_DEBUG(
"list types service finished");
716 controller_manager_msgs::ListControllers::Request &req,
717 controller_manager_msgs::ListControllers::Response &resp)
723 ROS_DEBUG(
"list controller service called");
725 ROS_DEBUG(
"list controller service locked");
730 resp.controller.resize(controllers.size());
732 for (
size_t i = 0; i < controllers.size(); ++i)
734 controller_manager_msgs::ControllerState& cs = resp.controller[i];
735 cs.name = controllers[i].info.name;
736 cs.type = controllers[i].info.type;
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)
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);
750 if (controllers[i].c->isInitialized())
752 cs.state =
"initialized";
754 else if (controllers[i].c->isRunning())
756 cs.state =
"running";
758 else if (controllers[i].c->isStopped())
760 cs.state =
"stopped";
762 else if (controllers[i].c->isWaiting())
764 cs.state =
"waiting";
766 else if (controllers[i].c->isAborted())
768 cs.state =
"aborted";
773 cs.state =
"unknown";
777 ROS_DEBUG(
"list controller service finished");
783 controller_manager_msgs::LoadController::Request &req,
784 controller_manager_msgs::LoadController::Response &resp)
787 ROS_DEBUG(
"loading service called for controller '%s' ",req.name.c_str());
793 ROS_DEBUG(
"loading service finished for controller '%s' ",req.name.c_str());
799 controller_manager_msgs::UnloadController::Request &req,
800 controller_manager_msgs::UnloadController::Response &resp)
803 ROS_DEBUG(
"unloading service called for controller '%s' ",req.name.c_str());
809 ROS_DEBUG(
"unloading service finished for controller '%s' ",req.name.c_str());
815 controller_manager_msgs::SwitchController::Request &req,
816 controller_manager_msgs::SwitchController::Response &resp)
823 resp.ok =
switchController(req.start_controllers, req.stop_controllers, req.strictness,
824 req.start_asap, req.timeout);
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_
std::shared_ptr< ControllerBase > ControllerBaseSharedPtr
virtual void doSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
void startControllersAsap(const ros::Time &time)
ros::ServiceServer srv_switch_controller_
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.
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_
void manageSwitch(const ros::Time &time)
hardware_interface::RobotHW * robot_hw_
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.
ros::ServiceServer srv_list_controllers_
bool unloadController(const std::string &name)
Unload a controller by name.
SwitchParams switch_params_
bool getParam(const std::string &key, std::string &s) 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)
std::shared_ptr< ControllerLoaderInterface > ControllerLoaderInterfaceSharedPtr
virtual bool prepareSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
ros::ServiceServer srv_unload_controller_
ros::ServiceServer srv_list_controller_types_
std::mutex services_lock_
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)
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.