moveit_simple_controller_manager.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Unbounded Robotics Inc.
00005  *  Copyright (c) 2012, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */
00037 
00038 #include <ros/ros.h>
00039 #include <moveit_simple_controller_manager/action_based_controller_handle.h>
00040 #include <moveit_simple_controller_manager/gripper_controller_handle.h>
00041 #include <moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h>
00042 #include <pluginlib/class_list_macros.h>
00043 #include <algorithm>
00044 #include <map>
00045 
00046 namespace moveit_simple_controller_manager
00047 {
00048 
00049 
00050 class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItControllerManager
00051 {
00052 public:
00053 
00054   MoveItSimpleControllerManager() : node_handle_("~")
00055   {
00056     if (!node_handle_.hasParam("controller_list"))
00057     {
00058       ROS_ERROR_STREAM("MoveitSimpleControllerManager: No controller_list specified.");
00059       return;
00060     }
00061 
00062     XmlRpc::XmlRpcValue controller_list;
00063     node_handle_.getParam("controller_list", controller_list);
00064     if (controller_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00065     {
00066       ROS_ERROR("MoveitSimpleControllerManager: controller_list should be specified as an array");
00067       return;
00068     }
00069 
00070     /* actually create each controller */
00071     for (int i = 0 ; i < controller_list.size() ; ++i)
00072     {
00073       if (!controller_list[i].hasMember("name") || !controller_list[i].hasMember("joints"))
00074       {
00075         ROS_ERROR("MoveitSimpleControllerManager: Name and joints must be specifed for each controller");
00076         continue;
00077       }
00078 
00079       try
00080       {
00081         std::string name = std::string(controller_list[i]["name"]);
00082 
00083         std::string action_ns;
00084         if (controller_list[i].hasMember("ns"))
00085         {
00086           /* TODO: this used to be called "ns", renaming to "action_ns" and will remove in the future */
00087           action_ns = std::string(controller_list[i]["ns"]);
00088           ROS_WARN("MoveitSimpleControllerManager: use of 'ns' is deprecated, use 'action_ns' instead.");
00089         }
00090         else if (controller_list[i].hasMember("action_ns"))
00091           action_ns = std::string(controller_list[i]["action_ns"]);
00092         else
00093           ROS_WARN("MoveitSimpleControllerManager: please note that 'action_ns' no longer has a default value.");
00094 
00095         if (controller_list[i]["joints"].getType() != XmlRpc::XmlRpcValue::TypeArray)
00096         {
00097           ROS_ERROR_STREAM("MoveitSimpleControllerManager: The list of joints for controller " << name << " is not specified as an array");
00098           continue;
00099         }
00100 
00101         if (!controller_list[i].hasMember("type"))
00102         {
00103           ROS_ERROR_STREAM("MoveitSimpleControllerManager: No type specified for controller " << name);
00104           continue;
00105         }
00106 
00107         std::string type = std::string(controller_list[i]["type"]);
00108 
00109         ActionBasedControllerHandleBasePtr new_handle;
00110         if ( type == "GripperCommand" )
00111         {
00112           new_handle.reset(new GripperControllerHandle(name, action_ns));
00113           if (static_cast<GripperControllerHandle*>(new_handle.get())->isConnected())
00114           {
00115             if (controller_list[i].hasMember("parallel"))
00116             {
00117               if (controller_list[i]["joints"].size() != 2)
00118               {
00119                 ROS_ERROR_STREAM("MoveItSimpleControllerManager: Parallel Gripper requires exactly two joints");
00120                 continue;
00121               }
00122               static_cast<GripperControllerHandle*>(new_handle.get())->setParallelJawGripper(controller_list[i]["joints"][0], controller_list[i]["joints"][1]);
00123             }
00124             else
00125             {
00126               if (controller_list[i].hasMember("command_joint"))
00127                 static_cast<GripperControllerHandle*>(new_handle.get())->setCommandJoint(controller_list[i]["command_joint"]);
00128               else
00129                 static_cast<GripperControllerHandle*>(new_handle.get())->setCommandJoint(controller_list[i]["joints"][0]);
00130             }
00131 
00132             if (controller_list[i].hasMember("allow_failure"))
00133                 static_cast<GripperControllerHandle*>(new_handle.get())->allowFailure(true);
00134 
00135             ROS_INFO_STREAM("MoveitSimpleControllerManager: Added GripperCommand controller for " << name );
00136             controllers_[name] = new_handle;
00137           }
00138         }
00139         else if ( type == "FollowJointTrajectory" )
00140         {
00141           new_handle.reset(new FollowJointTrajectoryControllerHandle(name, action_ns));
00142           if (static_cast<FollowJointTrajectoryControllerHandle*>(new_handle.get())->isConnected())
00143           {
00144             ROS_INFO_STREAM("MoveitSimpleControllerManager: Added FollowJointTrajectory controller for " << name );
00145             controllers_[name] = new_handle;
00146           }
00147         }
00148         else
00149         {
00150           ROS_ERROR("Unknown controller type: '%s'", type.c_str());
00151           continue;
00152         }
00153         if (!controllers_[name])
00154         {
00155           controllers_.erase(name);
00156           continue;
00157         }
00158         
00159         /* add list of joints, used by controller manager and moveit */
00160         for (int j = 0 ; j < controller_list[i]["joints"].size() ; ++j)
00161           controllers_[name]->addJoint(std::string(controller_list[i]["joints"][j]));
00162       }
00163       catch (...)
00164       {
00165         ROS_ERROR("MoveitSimpleControllerManager: Unable to parse controller information");
00166       }
00167     }
00168   }
00169 
00170   virtual ~MoveItSimpleControllerManager()
00171   {
00172   }
00173 
00174   /*
00175    * Get a controller, by controller name (which was specified in the controllers.yaml
00176    */
00177   virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
00178   {
00179     std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
00180     if (it != controllers_.end())
00181       return static_cast<moveit_controller_manager::MoveItControllerHandlePtr>(it->second);
00182     else
00183       ROS_FATAL_STREAM("No such controller: " << name);
00184     return moveit_controller_manager::MoveItControllerHandlePtr();
00185   }
00186 
00187   /*
00188    * Get the list of controller names.
00189    */
00190   virtual void getControllersList(std::vector<std::string> &names)
00191   {
00192     for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.begin() ; it != controllers_.end() ; ++it)
00193       names.push_back(it->first);
00194     ROS_INFO_STREAM("Returned " << names.size() << " controllers in list");
00195   }
00196 
00197   /*
00198    * This plugin assumes that all controllers are already active -- and if they are not, well, it has no way to deal with it anyways!
00199    */
00200   virtual void getActiveControllers(std::vector<std::string> &names)
00201   {
00202     getControllersList(names);
00203   }
00204 
00205   /*
00206    * Controller must be loaded to be active, see comment above about active controllers...
00207    */
00208   virtual void getLoadedControllers(std::vector<std::string> &names)
00209   {
00210     getControllersList(names);
00211   }
00212 
00213   /*
00214    * Get the list of joints that a controller can control.
00215    */
00216   virtual void getControllerJoints(const std::string &name, std::vector<std::string> &joints)
00217   {
00218     std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
00219     if (it != controllers_.end())
00220     {
00221       it->second->getJoints(joints);
00222     }
00223     else
00224     {
00225       ROS_WARN("The joints for controller '%s' are not known. Perhaps the controller configuration is not loaded on the param server?", name.c_str());
00226       joints.clear();
00227     }
00228   }
00229 
00230   /*
00231    * Controllers are all active and default -- that's what makes this thing simple.
00232    */
00233   virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
00234   {
00235     moveit_controller_manager::MoveItControllerManager::ControllerState state;
00236     state.active_ = true;
00237     state.default_ = true;
00238     return state;
00239   }
00240 
00241   /* Cannot switch our controllers */
00242   virtual bool switchControllers(const std::vector<std::string> &activate, const std::vector<std::string> &deactivate) { return false; }
00243 
00244 protected:
00245 
00246   ros::NodeHandle node_handle_;
00247   std::map<std::string, ActionBasedControllerHandleBasePtr> controllers_;
00248 };
00249 
00250 } // end namespace moveit_simple_controller_manager
00251 
00252 PLUGINLIB_EXPORT_CLASS(moveit_simple_controller_manager::MoveItSimpleControllerManager,
00253                        moveit_controller_manager::MoveItControllerManager);


moveit_simple_controller_manager
Author(s): Michael Ferguson
autogenerated on Wed Aug 26 2015 12:42:24