action_based_controller_handle.h
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 #ifndef MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE
00039 #define MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE
00040 
00041 #include <moveit/controller_manager/controller_manager.h>
00042 #include <actionlib/client/simple_action_client.h>
00043 #include <moveit/macros/class_forward.h>
00044 
00045 namespace moveit_simple_controller_manager
00046 {
00047 
00048 /*
00049  * This exist solely to inject addJoint/getJoints into base non-templated class.
00050  */
00051 class ActionBasedControllerHandleBase : public moveit_controller_manager::MoveItControllerHandle
00052 {
00053 public:
00054   ActionBasedControllerHandleBase(const std::string &name) :
00055     moveit_controller_manager::MoveItControllerHandle(name)
00056   {
00057   }
00058 
00059   virtual void addJoint(const std::string &name) = 0;
00060   virtual void getJoints(std::vector<std::string> &joints) = 0;
00061 };
00062 
00063 MOVEIT_CLASS_FORWARD(ActionBasedControllerHandleBase);
00064 
00065 
00066 /*
00067  * This is a simple base class, which handles all of the action creation/etc
00068  */
00069 template<typename T>
00070 class ActionBasedControllerHandle : public ActionBasedControllerHandleBase
00071 {
00072 
00073 public:
00074   ActionBasedControllerHandle(const std::string &name, const std::string &ns) :
00075     ActionBasedControllerHandleBase(name),
00076     namespace_(ns),
00077     done_(true)
00078   {
00079     controller_action_client_.reset(new actionlib::SimpleActionClient<T>(getActionName(), true));
00080     unsigned int attempts = 0;
00081     while (ros::ok() && !controller_action_client_->waitForServer(ros::Duration(5.0)) && ++attempts < 3)
00082       ROS_INFO_STREAM("MoveitSimpleControllerManager: Waiting for " << getActionName() << " to come up");
00083 
00084     if (!controller_action_client_->isServerConnected())
00085     {
00086       ROS_ERROR_STREAM("MoveitSimpleControllerManager: Action client not connected: " << getActionName());
00087       controller_action_client_.reset();
00088     }
00089 
00090     last_exec_ = moveit_controller_manager::ExecutionStatus::SUCCEEDED;
00091   }
00092 
00093   bool isConnected() const
00094   {
00095     return controller_action_client_;
00096   }
00097 
00098   virtual bool cancelExecution()
00099   {
00100     if (!controller_action_client_)
00101       return false;
00102     if (!done_)
00103     {
00104       ROS_INFO_STREAM("MoveitSimpleControllerManager: Cancelling execution for " << name_);
00105       controller_action_client_->cancelGoal();
00106       last_exec_ = moveit_controller_manager::ExecutionStatus::PREEMPTED;
00107       done_ = true;
00108     }
00109     return true;
00110   }
00111 
00112   virtual bool waitForExecution(const ros::Duration &timeout = ros::Duration(0))
00113   {
00114     if (controller_action_client_ && !done_)
00115       return controller_action_client_->waitForResult(timeout);
00116     return true;
00117   }
00118 
00119   virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
00120   {
00121     return last_exec_;
00122   }
00123 
00124   virtual void addJoint(const std::string &name)
00125   {
00126     joints_.push_back(name);
00127   }
00128 
00129   virtual void getJoints(std::vector<std::string> &joints)
00130   {
00131     joints = joints_;
00132   }
00133 
00134 protected:
00135 
00136   std::string getActionName(void) const
00137   {
00138     if (namespace_.empty())
00139       return name_;
00140     else
00141       return name_ +"/" + namespace_;
00142   }
00143 
00144   void finishControllerExecution(const actionlib::SimpleClientGoalState& state)
00145   {
00146     ROS_DEBUG_STREAM("MoveitSimpleControllerManager: Controller " << name_ << " is done with state " << state.toString() << ": " << state.getText());
00147     if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
00148       last_exec_ = moveit_controller_manager::ExecutionStatus::SUCCEEDED;
00149     else
00150       if (state == actionlib::SimpleClientGoalState::ABORTED)
00151         last_exec_ = moveit_controller_manager::ExecutionStatus::ABORTED;
00152       else
00153         if (state == actionlib::SimpleClientGoalState::PREEMPTED)
00154           last_exec_ = moveit_controller_manager::ExecutionStatus::PREEMPTED;
00155         else
00156           last_exec_ = moveit_controller_manager::ExecutionStatus::FAILED;
00157     done_ = true;
00158   }
00159 
00160   /* execution status */
00161   moveit_controller_manager::ExecutionStatus last_exec_;
00162   bool done_;
00163 
00164   /* the controller namespace, for instance, topics will map to name/ns/goal, name/ns/result, etc */
00165   std::string namespace_;
00166 
00167   /* the joints controlled by this controller */
00168   std::vector<std::string> joints_;
00169 
00170   /* action client */
00171   boost::shared_ptr<actionlib::SimpleActionClient<T> > controller_action_client_;
00172 };
00173 
00174 
00175 } // end namespace moveit_simple_controller_manager
00176 
00177 #endif // MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE


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