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);
 
  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){
 
  549         in_stop_list = 
false;
 
  553     if(is_running && !in_stop_list && in_start_list){ 
 
  554       if(strictness ==  controller_manager_msgs::SwitchController::Request::STRICT){
 
  560         in_start_list = 
false;
 
  564     if(in_stop_list && in_start_list){ 
 
  565         ROS_ERROR_STREAM(
"Could no start or stop controller '" << info.
name << 
"' because of conflicting switching command");
 
  571     if(is_running && in_stop_list && !in_start_list){ 
 
  574     else if(!is_running && !in_stop_list && in_start_list){ 
 
  578     bool add_to_list = is_running;
 
  585       info_list.push_back(info);
 
  591     ROS_ERROR(
"Could not switch controllers, due to resource conflict");
 
  599     ROS_ERROR(
"Could not switch controllers. The hardware interface combination for the requested controllers is unfeasible.");
 
  613   ROS_DEBUG(
"Request atomic controller switch from realtime loop");
 
  614   auto start_time = std::chrono::system_clock::now();
 
  615   bool timed_out = 
false;
 
  622     std::chrono::duration<double> diff = std::chrono::system_clock::now() - start_time;
 
  623     if (diff.count() < timeout+1.0 || timeout == 0){
 
  624         std::this_thread::sleep_for(std::chrono::microseconds(100));
 
  626         ROS_DEBUG(
"Timed out while switching controllers. Exiting...");
 
  634       ROS_DEBUG(
"Exited wait until switch is finished loop using non-ROS-time timeout");
 
  637   ROS_DEBUG(
"Successfully switched controllers");
 
  643   controller_manager_msgs::ReloadControllerLibraries::Request &req,
 
  644   controller_manager_msgs::ReloadControllerLibraries::Response &resp)
 
  647   ROS_DEBUG(
"reload libraries service called");
 
  649   ROS_DEBUG(
"reload libraries service locked");
 
  652   std::vector<std::string> controllers;
 
  654   if (!controllers.empty() && !req.force_kill){
 
  655     ROS_ERROR(
"Controller manager: Cannot reload controller libraries because there are still %i controllers running", (
int)controllers.size());
 
  661   if (!controllers.empty()){
 
  662     ROS_INFO(
"Controller manager: Killing all running controllers");
 
  663     std::vector<std::string> empty;
 
  664     if (!
switchController(empty,controllers, controller_manager_msgs::SwitchController::Request::BEST_EFFORT)){
 
  665       ROS_ERROR(
"Controller manager: Cannot reload controller libraries because failed to stop running controllers");
 
  669     for (
const auto& controller : controllers){
 
  671         ROS_ERROR(
"Controller manager: Cannot reload controller libraries because failed to unload controller '%s'",
 
  679   assert(controllers.empty());
 
  684     controller_loader->reload();
 
  685     ROS_INFO(
"Controller manager: reloaded controller libraries for '%s'", controller_loader->getName().c_str());
 
  690   ROS_DEBUG(
"reload libraries service finished");
 
  696   controller_manager_msgs::ListControllerTypes::Request &req,
 
  697   controller_manager_msgs::ListControllerTypes::Response &resp)
 
  709     std::vector<std::string> cur_types = controller_loader->getDeclaredClasses();
 
  710     for (
const auto& cur_type : cur_types)
 
  712       resp.types.push_back(cur_type);
 
  713       resp.base_classes.push_back(controller_loader->getName());
 
  717   ROS_DEBUG(
"list types service finished");
 
  723   controller_manager_msgs::ListControllers::Request &req,
 
  724   controller_manager_msgs::ListControllers::Response &resp)
 
  730   ROS_DEBUG(
"list controller service called");
 
  732   ROS_DEBUG(
"list controller service locked");
 
  737   resp.controller.resize(controllers.size());
 
  739   for (
size_t i = 0; i < controllers.size(); ++i)
 
  741     controller_manager_msgs::ControllerState& cs = resp.controller[i];
 
  742     cs.name = controllers[i].info.name;
 
  743     cs.type = controllers[i].info.type;
 
  745     cs.claimed_resources.clear();
 
  746     typedef std::vector<hardware_interface::InterfaceResources> ClaimedResVec;
 
  747     typedef ClaimedResVec::const_iterator ClaimedResIt;
 
  748     const ClaimedResVec& c_resources = controllers[i].info.claimed_resources;
 
  749     for (
const auto& c_resource : c_resources)
 
  751       controller_manager_msgs::HardwareInterfaceResources iface_res;
 
  752       iface_res.hardware_interface = c_resource.hardware_interface;
 
  753       std::copy(c_resource.resources.begin(), c_resource.resources.end(), std::back_inserter(iface_res.resources));
 
  754       cs.claimed_resources.push_back(iface_res);
 
  757     if (controllers[i].c->isInitialized())
 
  759       cs.state = 
"initialized";
 
  761     else if (controllers[i].c->isRunning())
 
  763       cs.state = 
"running";
 
  765     else if (controllers[i].c->isStopped())
 
  767       cs.state = 
"stopped";
 
  769     else if (controllers[i].c->isWaiting())
 
  771       cs.state = 
"waiting";
 
  773     else if (controllers[i].c->isAborted())
 
  775       cs.state = 
"aborted";
 
  780       cs.state = 
"unknown";
 
  784   ROS_DEBUG(
"list controller service finished");
 
  790   controller_manager_msgs::LoadController::Request &req,
 
  791   controller_manager_msgs::LoadController::Response &resp)
 
  794   ROS_DEBUG(
"loading service called for controller '%s' ",req.name.c_str());
 
  800   ROS_DEBUG(
"loading service finished for controller '%s' ",req.name.c_str());
 
  806   controller_manager_msgs::UnloadController::Request &req,
 
  807   controller_manager_msgs::UnloadController::Response &resp)
 
  810   ROS_DEBUG(
"unloading service called for controller '%s' ",req.name.c_str());
 
  816   ROS_DEBUG(
"unloading service finished for controller '%s' ",req.name.c_str());
 
  822   controller_manager_msgs::SwitchController::Request &req,
 
  823   controller_manager_msgs::SwitchController::Response &resp)
 
  830   resp.ok = 
switchController(req.start_controllers, req.stop_controllers, req.strictness,
 
  831                              req.start_asap, req.timeout);