gripper_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_GRIPPER_CONTROLLER_HANDLE
00039 #define MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE
00040 
00041 #include <moveit_simple_controller_manager/action_based_controller_handle.h>
00042 #include <control_msgs/GripperCommandAction.h>
00043 #include <set>
00044 
00045 namespace moveit_simple_controller_manager
00046 {
00047 /*
00048  * This is an interface for a gripper using control_msgs/GripperCommandAction
00049  * action interface (single DOF).
00050  */
00051 class GripperControllerHandle : public ActionBasedControllerHandle<control_msgs::GripperCommandAction>
00052 {
00053 public:
00054   /* Topics will map to name/ns/goal, name/ns/result, etc */
00055   GripperControllerHandle(const std::string& name, const std::string& ns)
00056     : ActionBasedControllerHandle<control_msgs::GripperCommandAction>(name, ns)
00057     , allow_failure_(false)
00058     , parallel_jaw_gripper_(false)
00059   {
00060   }
00061 
00062   virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory& trajectory)
00063   {
00064     ROS_DEBUG_STREAM_NAMED("GripperController", "Received new trajectory for " << name_);
00065 
00066     if (!controller_action_client_)
00067       return false;
00068 
00069     if (!trajectory.multi_dof_joint_trajectory.points.empty())
00070     {
00071       ROS_ERROR_NAMED("GripperController", "Gripper cannot execute multi-dof trajectories.");
00072       return false;
00073     }
00074 
00075     if (trajectory.joint_trajectory.points.empty())
00076     {
00077       ROS_ERROR_NAMED("GripperController", "GripperController requires at least one joint trajectory point.");
00078       return false;
00079     }
00080 
00081     if (trajectory.joint_trajectory.points.size() > 1)
00082     {
00083       ROS_DEBUG_STREAM_NAMED("GripperController", "Trajectory: " << trajectory.joint_trajectory);
00084     }
00085 
00086     if (trajectory.joint_trajectory.joint_names.empty())
00087     {
00088       ROS_ERROR_NAMED("GripperController", "No joint names specified");
00089       return false;
00090     }
00091 
00092     std::vector<int> gripper_joint_indexes;
00093     for (std::size_t i = 0; i < trajectory.joint_trajectory.joint_names.size(); ++i)
00094     {
00095       if (command_joints_.find(trajectory.joint_trajectory.joint_names[i]) != command_joints_.end())
00096       {
00097         gripper_joint_indexes.push_back(i);
00098         if (!parallel_jaw_gripper_)
00099           break;
00100       }
00101     }
00102 
00103     if (gripper_joint_indexes.empty())
00104     {
00105       ROS_WARN_NAMED("GripperController", "No command_joint was specified for the MoveIt controller gripper handle. \
00106                       Please see GripperControllerHandle::addCommandJoint() and \
00107                       GripperControllerHandle::setCommandJoint(). Assuming index 0.");
00108       gripper_joint_indexes.push_back(0);
00109     }
00110 
00111     // goal to be sent
00112     control_msgs::GripperCommandGoal goal;
00113     goal.command.position = 0.0;
00114     goal.command.max_effort = 0.0;
00115 
00116     // send last point
00117     int tpoint = trajectory.joint_trajectory.points.size() - 1;
00118     ROS_DEBUG_NAMED("GripperController", "Sending command from trajectory point %d", tpoint);
00119 
00120     // fill in goal from last point
00121     for (std::size_t i = 0; i < gripper_joint_indexes.size(); ++i)
00122     {
00123       int idx = gripper_joint_indexes[i];
00124 
00125       if (trajectory.joint_trajectory.points[tpoint].positions.size() <= idx)
00126       {
00127         ROS_ERROR_NAMED("GripperController", "GripperController expects a joint trajectory with one \
00128                          point that specifies at least the position of joint \
00129                          '%s', but insufficient positions provided",
00130                         trajectory.joint_trajectory.joint_names[idx].c_str());
00131         return false;
00132       }
00133       goal.command.position += trajectory.joint_trajectory.points[tpoint].positions[idx];
00134 
00135       if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx)
00136         goal.command.max_effort = trajectory.joint_trajectory.points[tpoint].effort[idx];
00137     }
00138 
00139     controller_action_client_->sendGoal(goal,
00140                                         boost::bind(&GripperControllerHandle::controllerDoneCallback, this, _1, _2),
00141                                         boost::bind(&GripperControllerHandle::controllerActiveCallback, this),
00142                                         boost::bind(&GripperControllerHandle::controllerFeedbackCallback, this, _1));
00143 
00144     done_ = false;
00145     last_exec_ = moveit_controller_manager::ExecutionStatus::RUNNING;
00146     return true;
00147   }
00148 
00149   void setCommandJoint(const std::string& name)
00150   {
00151     command_joints_.clear();
00152     addCommandJoint(name);
00153   }
00154 
00155   void addCommandJoint(const std::string& name)
00156   {
00157     command_joints_.insert(name);
00158   }
00159 
00160   void allowFailure(bool allow)
00161   {
00162     allow_failure_ = allow;
00163   }
00164 
00165   void setParallelJawGripper(const std::string& left, const std::string& right)
00166   {
00167     addCommandJoint(left);
00168     addCommandJoint(right);
00169     parallel_jaw_gripper_ = true;
00170   }
00171 
00172 private:
00173   void controllerDoneCallback(const actionlib::SimpleClientGoalState& state,
00174                               const control_msgs::GripperCommandResultConstPtr& result)
00175   {
00176     if (state == actionlib::SimpleClientGoalState::ABORTED && allow_failure_)
00177       finishControllerExecution(actionlib::SimpleClientGoalState::SUCCEEDED);
00178     else
00179       finishControllerExecution(state);
00180   }
00181 
00182   void controllerActiveCallback()
00183   {
00184     ROS_DEBUG_STREAM_NAMED("GripperController", name_ << " started execution");
00185   }
00186 
00187   void controllerFeedbackCallback(const control_msgs::GripperCommandFeedbackConstPtr& feedback)
00188   {
00189   }
00190 
00191   /*
00192    * Some gripper drivers may indicate a failure if they do not close all the way when
00193    * an object is in the gripper.
00194    */
00195   bool allow_failure_;
00196 
00197   /*
00198    * A common setup is where there are two joints that each move
00199    * half the overall distance. Thus, the command to the gripper
00200    * should be the sum of the two joint distances.
00201    *
00202    * When this is set, command_joints_ should be of size 2,
00203    * and the command will be the sum of the two joints.
00204    */
00205   bool parallel_jaw_gripper_;
00206 
00207   /*
00208    * A GripperCommand message has only a single float64 for the
00209    * "command", thus only a single joint angle can be sent -- however,
00210    * due to the complexity of making grippers look correct in a URDF,
00211    * they typically have >1 joints. The "command_joint" is the joint
00212    * whose position value will be sent in the GripperCommand action. A
00213    * set of names is provided for acceptable joint names. If any of
00214    * the joints specified is found, the value corresponding to that
00215    * joint is considered the command.
00216    */
00217   std::set<std::string> command_joints_;
00218 };
00219 
00220 }  // end namespace moveit_simple_controller_manager
00221 
00222 #endif  // MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE


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