controller_manager.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2008, Willow Garage, Inc.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of Willow Garage, Inc. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 /*
00028  * Author: Stuart Glaser, Wim Meeussen
00029  */
00030 
00031 #include "pr2_controller_manager/controller_manager.h"
00032 #include "pr2_controller_manager/scheduler.h"
00033 #include <algorithm>
00034 #include <boost/thread/thread.hpp>
00035 #include <boost/thread/condition.hpp>
00036 #include <sstream>
00037 #include "ros/console.h"
00038 
00039 using namespace pr2_mechanism_model;
00040 using namespace pr2_controller_manager;
00041 using namespace pr2_hardware_interface;
00042 using namespace pr2_controller_interface;
00043 using namespace boost::accumulators;
00044 using namespace ros;
00045 
00046 
00047 ControllerManager::ControllerManager(HardwareInterface *hw, const ros::NodeHandle& nh) :
00048   model_(hw),
00049   state_(NULL),
00050   controller_node_(nh),
00051   cm_node_(nh, "pr2_controller_manager"),
00052   start_request_(0),
00053   stop_request_(0),
00054   please_switch_(false),
00055   current_controllers_list_(0),
00056   used_by_realtime_(-1),
00057   pub_joint_state_(nh, "joint_states", 1),
00058   pub_mech_stats_(nh, "mechanism_statistics", 1),
00059   last_published_joint_state_(ros::Time::now()),
00060   last_published_mechanism_stats_(ros::Time::now())
00061 {}
00062 
00063 ControllerManager::~ControllerManager()
00064 {
00065   if (state_)
00066     delete state_;
00067 }
00068 
00069 
00070 bool ControllerManager::initXml(TiXmlElement* config)
00071 {
00072   if (!model_.initXml(config)){
00073     ROS_ERROR("Failed to initialize pr2 mechanism model");
00074     return false;
00075   }
00076   state_ = new RobotState(&model_);
00077   motors_previously_halted_ = state_->isHalted();
00078 
00079   // pre-allocate for realtime publishing
00080   pub_mech_stats_.msg_.controller_statistics.resize(0);
00081   pub_mech_stats_.msg_.actuator_statistics.resize(model_.hw_->actuators_.size());
00082   int joints_size = 0;
00083   for (unsigned int i = 0; i < state_->joint_states_.size(); ++i)
00084   {
00085     int type = state_->joint_states_[i].joint_->type;
00086     if (type != urdf::Joint::REVOLUTE &&
00087         type != urdf::Joint::CONTINUOUS &&
00088         type != urdf::Joint::PRISMATIC){
00089       ROS_ERROR("Joint state contains joint '%s' of unknown type", state_->joint_states_[i].joint_->name.c_str());
00090       return false;
00091     }
00092     ++joints_size;
00093   }
00094   pub_mech_stats_.msg_.joint_statistics.resize(joints_size);
00095   pub_joint_state_.msg_.name.resize(joints_size);
00096   pub_joint_state_.msg_.position.resize(joints_size);
00097   pub_joint_state_.msg_.velocity.resize(joints_size);
00098   pub_joint_state_.msg_.effort.resize(joints_size);
00099 
00100   // get the publish rate for mechanism state
00101   double publish_rate_joint_state, publish_rate_mechanism_stats;
00102   cm_node_.param("mechanism_statistics_publish_rate", publish_rate_mechanism_stats, 1.0);
00103   cm_node_.param("joint_state_publish_rate", publish_rate_joint_state, 100.0);
00104   publish_period_mechanism_stats_ = Duration(1.0/fmax(0.000001, publish_rate_mechanism_stats));
00105   publish_period_joint_state_ = Duration(1.0/fmax(0.000001, publish_rate_joint_state));
00106 
00107   // create controller loader
00108   controller_loader_.reset(new pluginlib::ClassLoader<pr2_controller_interface::Controller>("pr2_controller_interface",
00109                                                                                            "pr2_controller_interface::Controller"));
00110   // Advertise services (this should be the last thing we do in init)
00111   srv_list_controllers_ = cm_node_.advertiseService("list_controllers", &ControllerManager::listControllersSrv, this);
00112   srv_list_controller_types_ = cm_node_.advertiseService("list_controller_types", &ControllerManager::listControllerTypesSrv, this);
00113   srv_load_controller_ = cm_node_.advertiseService("load_controller", &ControllerManager::loadControllerSrv, this);
00114   srv_unload_controller_ = cm_node_.advertiseService("unload_controller", &ControllerManager::unloadControllerSrv, this);
00115   srv_switch_controller_ = cm_node_.advertiseService("switch_controller", &ControllerManager::switchControllerSrv, this);
00116   srv_reload_libraries_ = cm_node_.advertiseService("reload_controller_libraries", &ControllerManager::reloadControllerLibrariesSrv, this);
00117 
00118   return true;
00119 }
00120 
00121 
00122 
00123 
00124 
00125 // Must be realtime safe.
00126 void ControllerManager::update()
00127 {
00128   used_by_realtime_ = current_controllers_list_;
00129   std::vector<ControllerSpec> &controllers = controllers_lists_[used_by_realtime_];
00130   std::vector<size_t> &scheduling = controllers_scheduling_[used_by_realtime_];
00131 
00132   ros::Time start = ros::Time::now();
00133   state_->propagateActuatorPositionToJointPosition();
00134   state_->zeroCommands();
00135   ros::Time start_update = ros::Time::now();
00136   pre_update_stats_.acc((start_update - start).toSec());
00137 
00138   // Restart all running controllers if motors are re-enabled
00139   if (!state_->isHalted() && motors_previously_halted_){
00140     for (size_t i=0; i<controllers.size(); i++){
00141       if (controllers[scheduling[i]].c->isRunning()){
00142         controllers[scheduling[i]].c->stopRequest();
00143         controllers[scheduling[i]].c->startRequest();
00144       }
00145     }
00146   }
00147   motors_previously_halted_ = state_->isHalted();
00148 
00149   // Update all controllers in scheduling order
00150   for (size_t i=0; i<controllers.size(); i++){
00151     ros::Time start = ros::Time::now();
00152     controllers[scheduling[i]].c->updateRequest();
00153     ros::Time end = ros::Time::now();
00154     controllers[scheduling[i]].stats->acc((end - start).toSec());
00155     if (end - start > ros::Duration(0.001)){
00156       controllers[scheduling[i]].stats->num_control_loop_overruns++;
00157       controllers[scheduling[i]].stats->time_last_control_loop_overrun = end;
00158     }
00159   }
00160   ros::Time end_update = ros::Time::now();
00161   update_stats_.acc((end_update - start_update).toSec());
00162 
00163   state_->enforceSafety();
00164   state_->propagateJointEffortToActuatorEffort();
00165   ros::Time end = ros::Time::now();
00166   post_update_stats_.acc((end - end_update).toSec());
00167 
00168   // publish state
00169   publishMechanismStatistics();
00170   publishJointState();
00171 
00172   // there are controllers to start/stop
00173   if (please_switch_)
00174   {
00175     // stop controllers
00176     for (unsigned int i=0; i<stop_request_.size(); i++)
00177       if (!stop_request_[i]->stopRequest())
00178         ROS_FATAL("Failed to stop controller in realtime loop. This should never happen.");
00179 
00180     // start controllers
00181     for (unsigned int i=0; i<start_request_.size(); i++)
00182       if (!start_request_[i]->startRequest())
00183         ROS_FATAL("Failed to start controller in realtime loop. This should never happen.");
00184 
00185     start_request_.clear();
00186     stop_request_.clear();
00187     please_switch_ = false;
00188   }
00189 }
00190 
00191 pr2_controller_interface::Controller* ControllerManager::getControllerByName(const std::string& name)
00192 {
00193   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00194   for (size_t i = 0; i < controllers.size(); ++i)
00195   {
00196     if (controllers[i].name == name)
00197       return controllers[i].c.get();
00198   }
00199   return NULL;
00200 }
00201 
00202 void ControllerManager::getControllerNames(std::vector<std::string> &names)
00203 {
00204   boost::mutex::scoped_lock guard(controllers_lock_);
00205   std::vector<ControllerSpec> &controllers = controllers_lists_[current_controllers_list_];
00206   for (size_t i = 0; i < controllers.size(); ++i)
00207   {
00208     names.push_back(controllers[i].name);
00209   }
00210 }
00211 
00212 void ControllerManager::getControllerSchedule(std::vector<size_t> &schedule)
00213 {
00214   boost::mutex::scoped_lock guard(controllers_lock_);
00215   schedule = controllers_scheduling_[current_controllers_list_];
00216 }
00217 
00218 
00219 bool ControllerManager::loadController(const std::string& name)
00220 {
00221   ROS_DEBUG("Will load controller '%s'", name.c_str());
00222 
00223   // lock controllers
00224   boost::mutex::scoped_lock guard(controllers_lock_);
00225 
00226   // get reference to controller list
00227   int free_controllers_list = (current_controllers_list_ + 1) % 2;
00228   while (ros::ok() && free_controllers_list == used_by_realtime_){
00229     if (!ros::ok())
00230       return false;
00231     usleep(200);
00232   }
00233   std::vector<ControllerSpec>
00234     &from = controllers_lists_[current_controllers_list_],
00235     &to = controllers_lists_[free_controllers_list];
00236   to.clear();
00237 
00238   // Copy all controllers from the 'from' list to the 'to' list
00239   for (size_t i = 0; i < from.size(); ++i)
00240     to.push_back(from[i]);
00241 
00242   // Checks that we're not duplicating controllers
00243   for (size_t j = 0; j < to.size(); ++j)
00244   {
00245     if (to[j].name == name)
00246     {
00247       to.clear();
00248       ROS_ERROR("A controller named '%s' was already loaded inside the controller manager", name.c_str());
00249       return false;
00250     }
00251   }
00252 
00253   NodeHandle c_node;
00254   // Constructs the controller
00255   try{
00256     c_node = NodeHandle(controller_node_, name);
00257   }
00258   catch(std::exception &e) {
00259     ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s':\n%s", name.c_str(), e.what());
00260     return false;
00261   }
00262   catch(...){
00263     ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s'", name.c_str());
00264     return false;
00265   }
00266   pr2_controller_interface::Controller *c = NULL;
00267   std::string type;
00268   if (c_node.getParam("type", type))
00269   {
00270     ROS_DEBUG("Constructing controller '%s' of type '%s'", name.c_str(), type.c_str());
00271     try {
00272       // Backwards compatibility for using non-namespaced controller types
00273       if (!controller_loader_->isClassAvailable(type))
00274       {
00275         std::vector<std::string> classes = controller_loader_->getDeclaredClasses();
00276         for(unsigned int i = 0; i < classes.size(); ++i)
00277         {
00278           if(type == controller_loader_->getName(classes[i]))
00279           {
00280             ROS_WARN("The deprecated controller type %s was not found.  Using the namespaced version %s instead.  "
00281                      "Please update your configuration to use the namespaced version.",
00282                      type.c_str(), classes[i].c_str());
00283             type = classes[i];
00284             break;
00285           }
00286         }
00287       }
00288 
00289       c = controller_loader_->createClassInstance(type, true);
00290     }
00291     catch (const std::runtime_error &ex)
00292     {
00293       ROS_ERROR("Could not load class %s: %s", type.c_str(), ex.what());
00294     }
00295   }
00296 
00297   // checks if controller was constructed
00298   if (c == NULL)
00299   {
00300     to.clear();
00301     if (type == "")
00302       ROS_ERROR("Could not load controller '%s' because the type was not specified. Did you load the controller configuration on the parameter server?",
00303               name.c_str());
00304     else
00305       ROS_ERROR("Could not load controller '%s' because controller type '%s' does not exist",
00306                 name.c_str(), type.c_str());
00307     return false;
00308   }
00309 
00310   // Initializes the controller
00311   ROS_DEBUG("Initializing controller '%s'", name.c_str());
00312   bool initialized;
00313   try{
00314     initialized = c->initRequest(this, state_, c_node);
00315   }
00316   catch(std::exception &e){
00317     ROS_ERROR("Exception thrown while initializing controller %s.\n%s", name.c_str(), e.what());
00318     initialized = false;
00319   }
00320   catch(...){
00321     ROS_ERROR("Exception thrown while initializing controller %s", name.c_str());
00322     initialized = false;
00323   }
00324   if (!initialized)
00325   {
00326     to.clear();
00327     delete c;
00328     ROS_ERROR("Initializing controller '%s' failed", name.c_str());
00329     return false;
00330   }
00331   ROS_DEBUG("Initialized controller '%s' succesful", name.c_str());
00332 
00333   // Adds the controller to the new list
00334   to.resize(to.size() + 1);
00335   to[to.size()-1].name = name;
00336   to[to.size()-1].c.reset(c);
00337 
00338   //  Do the controller scheduling
00339   if (!scheduleControllers(to, controllers_scheduling_[free_controllers_list])){
00340     to.clear();
00341     delete c;
00342     ROS_ERROR("Scheduling controller '%s' failed", name.c_str());
00343     return false;
00344   }
00345 
00346   // Resize controller state vector
00347   pub_mech_stats_.lock();
00348   pub_mech_stats_.msg_.controller_statistics.resize(to.size());
00349   for (size_t i=0; i<to.size(); i++)
00350     pub_mech_stats_.msg_.controller_statistics[i].name = to[i].name;
00351 
00352   // Destroys the old controllers list when the realtime thread is finished with it.
00353   int former_current_controllers_list_ = current_controllers_list_;
00354   current_controllers_list_ = free_controllers_list;
00355   while (ros::ok() && used_by_realtime_ == former_current_controllers_list_){
00356     if (!ros::ok())
00357       return false;
00358     usleep(200);
00359   }
00360   from.clear();
00361   pub_mech_stats_.unlock();
00362 
00363   ROS_DEBUG("Successfully load controller '%s'", name.c_str());
00364   return true;
00365 }
00366 
00367 
00368 
00369 
00370 bool ControllerManager::unloadController(const std::string &name)
00371 {
00372   ROS_DEBUG("Will unload controller '%s'", name.c_str());
00373 
00374   // lock the controllers
00375   boost::mutex::scoped_lock guard(controllers_lock_);
00376 
00377   // get reference to controller list
00378   int free_controllers_list = (current_controllers_list_ + 1) % 2;
00379   while (ros::ok() && free_controllers_list == used_by_realtime_){
00380     if (!ros::ok())
00381       return false;
00382     usleep(200);
00383   }
00384   std::vector<ControllerSpec>
00385     &from = controllers_lists_[current_controllers_list_],
00386     &to = controllers_lists_[free_controllers_list];
00387   to.clear();
00388 
00389   // check if no other controller depends on this controller
00390   for (size_t i = 0; i < from.size(); ++i){
00391     for (size_t b=0; b<from[i].c->before_list_.size(); b++){
00392       if (name == from[i].c->before_list_[b]){
00393         ROS_ERROR("Cannot unload controller %s because controller %s still depends on it",
00394                   name.c_str(), from[i].name.c_str());
00395         return false;
00396       }
00397     }
00398     for (size_t a=0; a<from[i].c->after_list_.size(); a++){
00399       if (name == from[i].c->after_list_[a]){
00400         ROS_ERROR("Cannot unload controller %s because controller %s still depends on it",
00401                   name.c_str(), from[i].name.c_str());
00402         return false;
00403       }
00404     }
00405   }
00406 
00407   // Transfers the running controllers over, skipping the one to be removed and the running ones.
00408   bool removed = false;
00409   for (size_t i = 0; i < from.size(); ++i)
00410   {
00411     if (from[i].name == name){
00412       if (from[i].c->isRunning()){
00413         to.clear();
00414         ROS_ERROR("Could not unload controller with name %s because it is still running",
00415                   name.c_str());
00416         return false;
00417       }
00418       removed = true;
00419     }
00420     else
00421       to.push_back(from[i]);
00422   }
00423 
00424   // Fails if we could not remove the controllers
00425   if (!removed)
00426   {
00427     to.clear();
00428     ROS_ERROR("Could not unload controller with name %s because no controller with this name exists",
00429               name.c_str());
00430     return false;
00431   }
00432 
00433   //  Do the controller scheduling
00434   ROS_DEBUG("Rescheduling controller execution order");
00435   if (!scheduleControllers(to, controllers_scheduling_[free_controllers_list])){
00436     to.clear();
00437     ROS_ERROR("Scheduling controllers failed when removing controller '%s' failed", name.c_str());
00438     return false;
00439   }
00440 
00441   // Resize controller state vector
00442   ROS_DEBUG("Resizing controller state vector");
00443   pub_mech_stats_.lock();
00444   pub_mech_stats_.msg_.controller_statistics.resize(to.size());
00445   for (size_t i=0; i<to.size(); i++)
00446     pub_mech_stats_.msg_.controller_statistics[i].name = to[i].name;
00447 
00448   // Destroys the old controllers list when the realtime thread is finished with it.
00449   ROS_DEBUG("Realtime switches over to new controller list");
00450   int former_current_controllers_list_ = current_controllers_list_;
00451   current_controllers_list_ = free_controllers_list;
00452   while (ros::ok() && used_by_realtime_ == former_current_controllers_list_){
00453     if (!ros::ok())
00454       return false;
00455     usleep(200);
00456   }
00457   ROS_DEBUG("Destruct controller");
00458   from.clear();
00459   ROS_DEBUG("Destruct controller finished");
00460   pub_mech_stats_.unlock();
00461 
00462   ROS_DEBUG("Successfully unloaded controller '%s'", name.c_str());
00463   return true;
00464 }
00465 
00466 
00467 
00468 bool ControllerManager::switchController(const std::vector<std::string>& start_controllers,
00469                                          const std::vector<std::string>& stop_controllers,
00470                                          int strictness)
00471 {
00472   if (!stop_request_.empty() || !start_request_.empty())
00473     ROS_FATAL("The switch controller stop and start list are not empty that the beginning of the swithcontroller call. This should not happen.");
00474 
00475   if (strictness == 0){
00476     ROS_WARN("Controller Manager: To switch controllers you need to specify a strictness level of STRICT or BEST_EFFORT. Defaulting to BEST_EFFORT.");
00477     strictness = pr2_mechanism_msgs::SwitchController::Request::BEST_EFFORT;
00478   }
00479 
00480   ROS_DEBUG("switching controllers:");
00481   for (unsigned int i=0; i<start_controllers.size(); i++)
00482     ROS_DEBUG(" - starting controller %s", start_controllers[i].c_str());
00483   for (unsigned int i=0; i<stop_controllers.size(); i++)
00484     ROS_DEBUG(" - stopping controller %s", stop_controllers[i].c_str());
00485 
00486   // lock controllers
00487   boost::mutex::scoped_lock guard(controllers_lock_);
00488 
00489   pr2_controller_interface::Controller* ct;
00490   // list all controllers to stop
00491   for (unsigned int i=0; i<stop_controllers.size(); i++)
00492   {
00493     ct = getControllerByName(stop_controllers[i]);
00494     if (ct == NULL){
00495       if (strictness ==  pr2_mechanism_msgs::SwitchController::Request::STRICT){
00496         ROS_ERROR("Could not stop controller with name %s because no controller with this name exists",
00497                   stop_controllers[i].c_str());
00498         stop_request_.clear();
00499         return false;
00500       }
00501       else{
00502         ROS_DEBUG("Could not stop controller with name %s because no controller with this name exists",
00503                   stop_controllers[i].c_str());
00504       }
00505     }
00506     else{
00507       ROS_DEBUG("Found controller %s that needs to be stopped in list of controllers",
00508                 stop_controllers[i].c_str());
00509       stop_request_.push_back(ct);
00510     }
00511   }
00512   ROS_DEBUG("Stop request vector has size %i", (int)stop_request_.size());
00513 
00514   // list all controllers to start
00515   for (unsigned int i=0; i<start_controllers.size(); i++)
00516   {
00517     ct = getControllerByName(start_controllers[i]);
00518     if (ct == NULL){
00519       if (strictness ==  pr2_mechanism_msgs::SwitchController::Request::STRICT){
00520         ROS_ERROR("Could not start controller with name %s because no controller with this name exists",
00521                   start_controllers[i].c_str());
00522         stop_request_.clear();
00523         start_request_.clear();
00524         return false;
00525       }
00526       else{
00527         ROS_DEBUG("Could not start controller with name %s because no controller with this name exists",
00528                   start_controllers[i].c_str());
00529       }
00530     }
00531     else{
00532       ROS_DEBUG("Found controller %s that needs to be started in list of controllers",
00533                 start_controllers[i].c_str());
00534       start_request_.push_back(ct);
00535     }
00536   }
00537   ROS_DEBUG("Start request vector has size %i", (int)start_request_.size());
00538 
00539   // start the atomic controller switching
00540   switch_strictness_ = strictness;
00541   please_switch_ = true;
00542 
00543   // wait until switch is finished
00544   ROS_DEBUG("Request atomic controller switch from realtime loop");
00545   while (ros::ok() && please_switch_){
00546     if (!ros::ok())
00547       return false;
00548     usleep(100);
00549   }
00550   ROS_DEBUG("Successfully switched controllers");
00551   return true;
00552 }
00553 
00554 
00555 void ControllerManager::publishJointState()
00556 {
00557   ros::Time now = ros::Time::now();
00558   if (now > last_published_joint_state_ + publish_period_joint_state_)
00559   {
00560     if (pub_joint_state_.trylock())
00561     {
00562       while (last_published_joint_state_ + publish_period_joint_state_ < now)
00563         last_published_joint_state_ = last_published_joint_state_ + publish_period_joint_state_;
00564 
00565       unsigned int j = 0;
00566       for (unsigned int i = 0; i < state_->joint_states_.size(); ++i)
00567       {
00568         int type = state_->joint_states_[i].joint_->type;
00569         if (type == urdf::Joint::REVOLUTE || type == urdf::Joint::CONTINUOUS || type == urdf::Joint::PRISMATIC)
00570         {
00571           assert(j < pub_joint_state_.msg_.name.size());
00572           assert(j < pub_joint_state_.msg_.position.size());
00573           assert(j < pub_joint_state_.msg_.velocity.size());
00574           assert(j < pub_joint_state_.msg_.effort.size());
00575           pr2_mechanism_model::JointState *in = &state_->joint_states_[i];
00576           pub_joint_state_.msg_.name[j] = state_->joint_states_[i].joint_->name;
00577           pub_joint_state_.msg_.position[j] = in->position_;
00578           pub_joint_state_.msg_.velocity[j] = in->velocity_;
00579           pub_joint_state_.msg_.effort[j] = in->measured_effort_;
00580 
00581           j++;
00582         }
00583       }
00584       pub_joint_state_.msg_.header.stamp = ros::Time::now();
00585       pub_joint_state_.unlockAndPublish();
00586     }
00587   }
00588 }
00589 
00590 
00591 void ControllerManager::publishMechanismStatistics()
00592 {
00593   ros::Time now = ros::Time::now();
00594   if (now > last_published_mechanism_stats_ + publish_period_mechanism_stats_)
00595   {
00596     if (pub_mech_stats_.trylock())
00597     {
00598       while (last_published_mechanism_stats_ + publish_period_mechanism_stats_ < now)
00599         last_published_mechanism_stats_ = last_published_mechanism_stats_ + publish_period_mechanism_stats_;
00600 
00601       // joint state
00602       unsigned int j = 0;
00603       for (unsigned int i = 0; i < state_->joint_states_.size(); ++i)
00604       {
00605         int type = state_->joint_states_[i].joint_->type;
00606         if (type == urdf::Joint::REVOLUTE || type == urdf::Joint::CONTINUOUS || type == urdf::Joint::PRISMATIC)
00607         {
00608           assert(j < pub_mech_stats_.msg_.joint_statistics.size());
00609           pr2_mechanism_model::JointState *in = &state_->joint_states_[i];
00610           pr2_mechanism_msgs::JointStatistics *out = &pub_mech_stats_.msg_.joint_statistics[j];
00611           out->timestamp = now;
00612           out->name = state_->joint_states_[i].joint_->name;
00613           out->position = in->position_;
00614           out->velocity = in->velocity_;
00615           out->measured_effort = in->measured_effort_;
00616           out->commanded_effort = in->commanded_effort_;
00617           out->is_calibrated = in->calibrated_;
00618           out->violated_limits = in->joint_statistics_.violated_limits_;
00619           out->odometer = in->joint_statistics_.odometer_;
00620           out->min_position = in->joint_statistics_.min_position_;
00621           out->max_position = in->joint_statistics_.max_position_;
00622           out->max_abs_velocity = in->joint_statistics_.max_abs_velocity_;
00623           out->max_abs_effort = in->joint_statistics_.max_abs_effort_;
00624           in->joint_statistics_.reset();
00625           j++;
00626         }
00627       }
00628 
00629       // actuator state
00630       unsigned int i = 0;
00631       for (ActuatorMap::const_iterator it = model_.hw_->actuators_.begin(); it != model_.hw_->actuators_.end(); ++i, ++it)
00632       {
00633         pr2_mechanism_msgs::ActuatorStatistics *out = &pub_mech_stats_.msg_.actuator_statistics[i];
00634         ActuatorState *in = &(it->second->state_);
00635         out->timestamp = now;
00636         out->name = it->first;
00637         out->encoder_count = in->encoder_count_;
00638         out->encoder_offset = in->zero_offset_;
00639         out->position = in->position_;
00640         out->timestamp = ros::Time(in->timestamp_);
00641         out->device_id = in->device_id_;
00642         out->encoder_velocity = in->encoder_velocity_;
00643         out->velocity = in->velocity_;
00644         out->calibration_reading = in->calibration_reading_;
00645         out->calibration_rising_edge_valid = in->calibration_rising_edge_valid_;
00646         out->calibration_falling_edge_valid = in->calibration_falling_edge_valid_;
00647         out->last_calibration_rising_edge = in->last_calibration_rising_edge_;
00648         out->last_calibration_falling_edge = in->last_calibration_falling_edge_;
00649         out->is_enabled = in->is_enabled_;
00650         out->halted = in->halted_;
00651         out->last_commanded_current = in->last_commanded_current_;
00652         out->last_executed_current = in->last_executed_current_;
00653         out->last_measured_current = in->last_measured_current_;
00654         out->last_commanded_effort = in->last_commanded_effort_;
00655         out->last_executed_effort = in->last_executed_effort_;
00656         out->last_measured_effort = in->last_measured_effort_;
00657         out->motor_voltage = in->motor_voltage_;
00658         out->num_encoder_errors = in->num_encoder_errors_;
00659       }
00660 
00661       // controller state
00662       std::vector<ControllerSpec> &controllers = controllers_lists_[used_by_realtime_];
00663       for (unsigned int i = 0; i < controllers.size(); ++i)
00664       {
00665         pr2_mechanism_msgs::ControllerStatistics *out = &pub_mech_stats_.msg_.controller_statistics[i];
00666         out->timestamp = now;
00667         out->running = controllers[i].c->isRunning();
00668         out->max_time = ros::Duration(max(controllers[i].stats->acc));
00669         out->mean_time = ros::Duration(mean(controllers[i].stats->acc));
00670         out->variance_time = ros::Duration(sqrt(variance(controllers[i].stats->acc)));
00671         out->num_control_loop_overruns = controllers[i].stats->num_control_loop_overruns;
00672         out->time_last_control_loop_overrun = controllers[i].stats->time_last_control_loop_overrun;
00673       }
00674 
00675       pub_mech_stats_.msg_.header.stamp = ros::Time::now();
00676 
00677       pub_mech_stats_.unlockAndPublish();
00678     }
00679   }
00680 }
00681 
00682 
00683 
00684 bool ControllerManager::reloadControllerLibrariesSrv(
00685   pr2_mechanism_msgs::ReloadControllerLibraries::Request &req,
00686   pr2_mechanism_msgs::ReloadControllerLibraries::Response &resp)
00687 {
00688   // lock services
00689   ROS_DEBUG("reload libraries service called");
00690   boost::mutex::scoped_lock guard(services_lock_);
00691   ROS_DEBUG("reload libraries service locked");
00692 
00693   // only reload libraries if no controllers are running
00694   std::vector<std::string> controllers;
00695   getControllerNames(controllers);
00696   if (!controllers.empty() && !req.force_kill){
00697     ROS_ERROR("Controller manager: Cannot reload controller libraries because there are still %i controllers running", (int)controllers.size());
00698     resp.ok = false;
00699     return true;
00700   }
00701 
00702   // kill running controllers if requested
00703   if (!controllers.empty()){
00704     ROS_INFO("Controller manager: Killing all running controllers");
00705     std::vector<std::string> empty;
00706     if (!switchController(empty,controllers, pr2_mechanism_msgs::SwitchController::Request::BEST_EFFORT)){
00707       ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to stop running controllers");
00708       resp.ok = false;
00709       return true;
00710     }
00711     for (unsigned int i=0; i<controllers.size(); i++){
00712       if (!unloadController(controllers[i])){
00713         ROS_ERROR("Controller manager: Cannot reload controller libraries because failed to unload controller %s",
00714                   controllers[i].c_str());
00715         resp.ok = false;
00716         return true;
00717       }
00718     }
00719     getControllerNames(controllers);
00720   }
00721   assert(controllers.empty());
00722 
00723   // create new controller loader
00724   controller_loader_.reset(new pluginlib::ClassLoader<pr2_controller_interface::Controller>("pr2_controller_interface",
00725                                                                                             "pr2_controller_interface::Controller"));
00726   ROS_INFO("Controller manager: reloaded controller libraries");
00727   resp.ok = true;
00728 
00729   ROS_DEBUG("reload libraries service finished");
00730   return true;
00731 }
00732 
00733 
00734 bool ControllerManager::listControllerTypesSrv(
00735   pr2_mechanism_msgs::ListControllerTypes::Request &req,
00736   pr2_mechanism_msgs::ListControllerTypes::Response &resp)
00737 {
00738   // pretend to use the request
00739   (void) req;
00740 
00741   // lock services
00742   ROS_DEBUG("list types service called");
00743   boost::mutex::scoped_lock guard(services_lock_);
00744   ROS_DEBUG("list types service locked");
00745 
00746   resp.types = controller_loader_->getDeclaredClasses();
00747 
00748   ROS_DEBUG("list types service finished");
00749   return true;
00750 }
00751 
00752 
00753 bool ControllerManager::listControllersSrv(
00754   pr2_mechanism_msgs::ListControllers::Request &req,
00755   pr2_mechanism_msgs::ListControllers::Response &resp)
00756 {
00757   // pretend to use the request
00758   (void) req;
00759 
00760   // lock services
00761   ROS_DEBUG("list controller service called");
00762   boost::mutex::scoped_lock guard(services_lock_);
00763   ROS_DEBUG("list controller service locked");
00764 
00765   std::vector<std::string> controllers;
00766   std::vector<size_t> schedule;
00767 
00768   getControllerNames(controllers);
00769   getControllerSchedule(schedule);
00770   assert(controllers.size() == schedule.size());
00771   resp.controllers.resize(controllers.size());
00772   resp.state.resize(controllers.size());
00773 
00774   for (size_t i=0; i<schedule.size(); i++){
00775     // add controller state
00776     Controller* c = getControllerByName(controllers[schedule[i]]);
00777     assert(c);
00778     resp.controllers[i] = controllers[schedule[i]];
00779     if (c->isRunning())
00780       resp.state[i] = "running";
00781     else
00782       resp.state[i] = "stopped";
00783   }
00784 
00785   ROS_DEBUG("list controller service finished");
00786   return true;
00787 }
00788 
00789 
00790 bool ControllerManager::loadControllerSrv(
00791   pr2_mechanism_msgs::LoadController::Request &req,
00792   pr2_mechanism_msgs::LoadController::Response &resp)
00793 {
00794   // lock services
00795   ROS_DEBUG("loading service called for controller %s ",req.name.c_str());
00796   boost::mutex::scoped_lock guard(services_lock_);
00797   ROS_DEBUG("loading service locked");
00798 
00799   resp.ok = loadController(req.name);
00800 
00801   ROS_DEBUG("loading service finished for controller %s ",req.name.c_str());
00802   return true;
00803 }
00804 
00805 
00806 bool ControllerManager::unloadControllerSrv(
00807   pr2_mechanism_msgs::UnloadController::Request &req,
00808   pr2_mechanism_msgs::UnloadController::Response &resp)
00809 {
00810   // lock services
00811   ROS_DEBUG("unloading service called for controller %s ",req.name.c_str());
00812   boost::mutex::scoped_lock guard(services_lock_);
00813   ROS_DEBUG("unloading service locked");
00814 
00815   resp.ok = unloadController(req.name);
00816 
00817   ROS_DEBUG("unloading service finished for controller %s ",req.name.c_str());
00818   return true;
00819 }
00820 
00821 
00822 bool ControllerManager::switchControllerSrv(
00823   pr2_mechanism_msgs::SwitchController::Request &req,
00824   pr2_mechanism_msgs::SwitchController::Response &resp)
00825 {
00826   // lock services
00827   ROS_DEBUG("switching service called");
00828   boost::mutex::scoped_lock guard(services_lock_);
00829   ROS_DEBUG("switching service locked");
00830 
00831   resp.ok = switchController(req.start_controllers, req.stop_controllers, req.strictness);
00832 
00833   ROS_DEBUG("switching service finished");
00834   return true;
00835 }
00836 


pr2_controller_manager
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Thu Dec 12 2013 12:04:08