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 class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItControllerManager
00049 {
00050 public:
00051   MoveItSimpleControllerManager() : node_handle_("~")
00052   {
00053     if (!node_handle_.hasParam("controller_list"))
00054     {
00055       ROS_ERROR_STREAM_NAMED("manager", "No controller_list specified.");
00056       return;
00057     }
00058 
00059     XmlRpc::XmlRpcValue controller_list;
00060     node_handle_.getParam("controller_list", controller_list);
00061     if (controller_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00062     {
00063       ROS_ERROR("Parameter controller_list should be specified as an array");
00064       return;
00065     }
00066 
00067     /* actually create each controller */
00068     for (int i = 0; i < controller_list.size(); ++i)
00069     {
00070       if (!controller_list[i].hasMember("name") || !controller_list[i].hasMember("joints"))
00071       {
00072         ROS_ERROR_STREAM_NAMED("manager", "Name and joints must be specifed for each controller");
00073         continue;
00074       }
00075 
00076       try
00077       {
00078         std::string name = std::string(controller_list[i]["name"]);
00079 
00080         std::string action_ns;
00081         if (controller_list[i].hasMember("ns"))
00082         {
00083           /* TODO: this used to be called "ns", renaming to "action_ns" and will remove in the future */
00084           action_ns = std::string(controller_list[i]["ns"]);
00085           ROS_WARN_NAMED("manager", "Use of 'ns' is deprecated, use 'action_ns' instead.");
00086         }
00087         else if (controller_list[i].hasMember("action_ns"))
00088           action_ns = std::string(controller_list[i]["action_ns"]);
00089         else
00090           ROS_WARN_NAMED("manager", "Please note that 'action_ns' no longer has a default value.");
00091 
00092         if (controller_list[i]["joints"].getType() != XmlRpc::XmlRpcValue::TypeArray)
00093         {
00094           ROS_ERROR_STREAM_NAMED("manager", "The list of joints for controller " << name << " is not specified as an "
00095                                                                                             "array");
00096           continue;
00097         }
00098 
00099         if (!controller_list[i].hasMember("type"))
00100         {
00101           ROS_ERROR_STREAM_NAMED("manager", "No type specified for controller " << name);
00102           continue;
00103         }
00104 
00105         std::string type = std::string(controller_list[i]["type"]);
00106 
00107         ActionBasedControllerHandleBasePtr new_handle;
00108         if (type == "GripperCommand")
00109         {
00110           new_handle.reset(new GripperControllerHandle(name, action_ns));
00111           if (static_cast<GripperControllerHandle*>(new_handle.get())->isConnected())
00112           {
00113             if (controller_list[i].hasMember("parallel"))
00114             {
00115               if (controller_list[i]["joints"].size() != 2)
00116               {
00117                 ROS_ERROR_STREAM_NAMED("manager", "Parallel Gripper requires exactly two joints");
00118                 continue;
00119               }
00120               static_cast<GripperControllerHandle*>(new_handle.get())
00121                   ->setParallelJawGripper(controller_list[i]["joints"][0], controller_list[i]["joints"][1]);
00122             }
00123             else
00124             {
00125               if (controller_list[i].hasMember("command_joint"))
00126                 static_cast<GripperControllerHandle*>(new_handle.get())
00127                     ->setCommandJoint(controller_list[i]["command_joint"]);
00128               else
00129                 static_cast<GripperControllerHandle*>(new_handle.get())
00130                     ->setCommandJoint(controller_list[i]["joints"][0]);
00131             }
00132 
00133             if (controller_list[i].hasMember("allow_failure"))
00134               static_cast<GripperControllerHandle*>(new_handle.get())->allowFailure(true);
00135 
00136             ROS_INFO_STREAM_NAMED("manager", "Added GripperCommand controller for " << name);
00137             controllers_[name] = new_handle;
00138           }
00139         }
00140         else if (type == "FollowJointTrajectory")
00141         {
00142           new_handle.reset(new FollowJointTrajectoryControllerHandle(name, action_ns));
00143           if (static_cast<FollowJointTrajectoryControllerHandle*>(new_handle.get())->isConnected())
00144           {
00145             ROS_INFO_STREAM_NAMED("manager", "Added FollowJointTrajectory controller for " << name);
00146             controllers_[name] = new_handle;
00147           }
00148         }
00149         else
00150         {
00151           ROS_ERROR_STREAM_NAMED("manager", "Unknown controller type: " << type.c_str());
00152           continue;
00153         }
00154         if (!controllers_[name])
00155         {
00156           controllers_.erase(name);
00157           continue;
00158         }
00159 
00160         /* add list of joints, used by controller manager and moveit */
00161         for (int j = 0; j < controller_list[i]["joints"].size(); ++j)
00162           controllers_[name]->addJoint(std::string(controller_list[i]["joints"][j]));
00163       }
00164       catch (...)
00165       {
00166         ROS_ERROR_STREAM_NAMED("manager", "Unable to parse controller information");
00167       }
00168     }
00169   }
00170 
00171   virtual ~MoveItSimpleControllerManager()
00172   {
00173   }
00174 
00175   /*
00176    * Get a controller, by controller name (which was specified in the controllers.yaml
00177    */
00178   virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
00179   {
00180     std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
00181     if (it != controllers_.end())
00182       return static_cast<moveit_controller_manager::MoveItControllerHandlePtr>(it->second);
00183     else
00184       ROS_FATAL_STREAM_NAMED("manager", "No such controller: " << name);
00185     return moveit_controller_manager::MoveItControllerHandlePtr();
00186   }
00187 
00188   /*
00189    * Get the list of controller names.
00190    */
00191   virtual void getControllersList(std::vector<std::string>& names)
00192   {
00193     for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.begin();
00194          it != controllers_.end(); ++it)
00195       names.push_back(it->first);
00196     ROS_INFO_STREAM_NAMED("manager", "Returned " << names.size() << " controllers in list");
00197   }
00198 
00199   /*
00200    * This plugin assumes that all controllers are already active -- and if they are not, well, it has no way to deal
00201    * with it anyways!
00202    */
00203   virtual void getActiveControllers(std::vector<std::string>& names)
00204   {
00205     getControllersList(names);
00206   }
00207 
00208   /*
00209    * Controller must be loaded to be active, see comment above about active controllers...
00210    */
00211   virtual void getLoadedControllers(std::vector<std::string>& names)
00212   {
00213     getControllersList(names);
00214   }
00215 
00216   /*
00217    * Get the list of joints that a controller can control.
00218    */
00219   virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
00220   {
00221     std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
00222     if (it != controllers_.end())
00223     {
00224       it->second->getJoints(joints);
00225     }
00226     else
00227     {
00228       ROS_WARN_NAMED("manager", "The joints for controller '%s' are not known. Perhaps the controller configuration is "
00229                                 "not loaded on the param server?",
00230                      name.c_str());
00231       joints.clear();
00232     }
00233   }
00234 
00235   /*
00236    * Controllers are all active and default -- that's what makes this thing simple.
00237    */
00238   virtual moveit_controller_manager::MoveItControllerManager::ControllerState
00239   getControllerState(const std::string& name)
00240   {
00241     moveit_controller_manager::MoveItControllerManager::ControllerState state;
00242     state.active_ = true;
00243     state.default_ = true;
00244     return state;
00245   }
00246 
00247   /* Cannot switch our controllers */
00248   virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
00249   {
00250     return false;
00251   }
00252 
00253 protected:
00254   ros::NodeHandle node_handle_;
00255   std::map<std::string, ActionBasedControllerHandleBasePtr> controllers_;
00256 };
00257 
00258 }  // end namespace moveit_simple_controller_manager
00259 
00260 PLUGINLIB_EXPORT_CLASS(moveit_simple_controller_manager::MoveItSimpleControllerManager,
00261                        moveit_controller_manager::MoveItControllerManager);


moveit_simple_controller_manager
Author(s): Michael Ferguson
autogenerated on Mon Jul 24 2017 02:22:36