parallel_gripper.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *  Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014, Fetch Robotics Inc.
00005  *  Copyright (c) 2014, Unbounded Robotics 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 Fetch Robotics Inc. 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
00037 
00038 #include <pluginlib/class_list_macros.h>
00039 #include <robot_controllers/parallel_gripper.h>
00040 
00041 PLUGINLIB_EXPORT_CLASS(robot_controllers::ParallelGripperController, robot_controllers::Controller)
00042 
00043 namespace robot_controllers
00044 {
00045 
00046 int ParallelGripperController::init(ros::NodeHandle& nh, ControllerManager* manager)
00047 {
00048   // We absolutely need access to the controller manager
00049   if (!manager)
00050   {
00051     initialized_ = false;
00052     return -1;
00053   }
00054 
00055   Controller::init(nh, manager);
00056   manager_ = manager;
00057 
00058   // Setup Joints */
00059   std::string l_name, r_name;
00060   nh.param<std::string>("l_gripper_joint", l_name, "l_gripper_finger_joint");
00061   nh.param<std::string>("r_gripper_joint", r_name, "r_gripper_finger_joint");
00062 
00063   left_ = manager_->getJointHandle(l_name);
00064   right_ = manager_->getJointHandle(r_name);
00065 
00066   // Checking to see if Joint Handles exists
00067   if (!left_)
00068   {
00069     ROS_ERROR_NAMED("ParallelGripperController",
00070                     "Unable to retreive joint (%s), Namespace: %s/l_gripper_joint",
00071                     l_name.c_str(), nh.getNamespace().c_str());
00072     return -1;  
00073   }
00074   
00075   if (!right_)
00076   {
00077     ROS_ERROR_NAMED("ParallelGripperController",
00078                     "Unable to retreive joint (%s), Namespace: %s/r_gripper_joint",
00079                     r_name.c_str(), nh.getNamespace().c_str());
00080     return -1;
00081   } 
00082 
00083   // Start action server
00084   server_.reset(new server_t(nh, "",
00085                 boost::bind(&ParallelGripperController::executeCb, this, _1),
00086                 false));
00087   server_->start();
00088 
00089   // Get Params
00090   nh.param<double>("max_position", max_position_, 0.1);
00091   nh.param<double>("max_effort", max_effort_, 10.0);
00092 
00093   // PID controller for centering the gripper
00094   if (centering_pid_.init(ros::NodeHandle(nh, "centering")))
00095   {
00096     use_centering_controller_ = true;
00097   }
00098 
00099   // Set default to max
00100   goal_ = max_position_;
00101   effort_ = max_effort_;
00102 
00103   initialized_ = true;
00104   return 0;
00105 }
00106 
00107 bool ParallelGripperController::start()
00108 {
00109   if (!initialized_)
00110   {
00111     ROS_ERROR_NAMED("ParallelGripperController",
00112                     "Unable to start, not initialized.");
00113     return false;
00114   }
00115 
00116   if (!server_->isActive())
00117   {
00118     ROS_ERROR_NAMED("ParallelGripperController",
00119                     "Unable to start, action server is not active.");
00120     return false;
00121   }
00122 
00123   return true;
00124 }
00125 
00126 bool ParallelGripperController::stop(bool force)
00127 {
00128   if (!initialized_)
00129     return true;
00130 
00131   if (server_->isActive())
00132   {
00133     if (force)
00134     {
00135       // Shut down the action
00136       server_->setPreempted();
00137       return true;
00138     }
00139 
00140     // Do not abort unless forced
00141     return false;
00142   }
00143 
00144   // Just holding position, go ahead and stop us
00145   return true;
00146 }
00147 
00148 bool ParallelGripperController::reset()
00149 {
00150   // Nothing to do here
00151   return true;
00152 }
00153 
00154 void ParallelGripperController::update(const ros::Time& now, const ros::Duration& dt)
00155 {
00156   if (!initialized_)
00157     return;
00158 
00159   if (use_centering_controller_)
00160   {
00161     double position = left_->getPosition() + right_->getPosition();
00162     double effort = fabs(effort_);
00163     if (goal_ < position)
00164     {
00165       effort = -effort;
00166     }
00167 
00168     double offset = centering_pid_.update(left_->getPosition() - right_->getPosition(), dt.toSec());
00169 
00170     left_->setEffort(effort - offset);
00171     right_->setEffort(effort + offset);
00172   }
00173   else
00174   {
00175     left_->setPosition(goal_/2.0, 0, effort_);
00176     right_->setPosition(goal_/2.0, 0, effort_);
00177   }
00178 }
00179 
00180 void ParallelGripperController::executeCb(const control_msgs::GripperCommandGoalConstPtr& goal)
00181 {
00182   control_msgs::GripperCommandFeedback feedback;
00183   control_msgs::GripperCommandResult result;
00184 
00185   if (!initialized_)
00186   {
00187     server_->setAborted(result, "Controller is not initialized.");
00188     return;
00189   }
00190 
00191   if (manager_->requestStart(getName()) != 0)
00192   {
00193     server_->setAborted(result, "Cannot execute, unable to start controller.");
00194     ROS_ERROR_NAMED("ParallelGripperController",
00195                     "Cannot execute, unable to start controller.");
00196     return;
00197   }
00198 
00199   // Effort of 0.0 means use max
00200   if (goal->command.max_effort <= 0.0 || goal->command.max_effort > max_effort_)
00201   {
00202     effort_ = max_effort_;
00203   }
00204   else
00205   {
00206     effort_ = goal->command.max_effort;
00207   }
00208 
00209   // Set goal position
00210   if (goal->command.position > max_position_)
00211   {
00212     goal_ = max_position_;
00213   }
00214   else if (goal->command.position < 0.0)
00215   {
00216     goal_ = 0.0;
00217   }
00218   else
00219   {
00220     goal_ = goal->command.position;
00221   }
00222 
00223   // Track position/time for stall detection
00224   float last_position = left_->getPosition() + right_->getPosition();
00225   ros::Time last_position_time = ros::Time::now();
00226 
00227   ros::Rate r(50);
00228   while (true)
00229   {
00230     // Abort detection
00231     if (server_->isPreemptRequested() || !ros::ok())
00232     {
00233       ROS_DEBUG_NAMED("ParallelGripperController", "Command preempted.");
00234       server_->setPreempted();
00235       break;
00236     }
00237 
00238     // Publish feedback before possibly completing
00239     feedback.position = left_->getPosition() + right_->getPosition();
00240     feedback.effort = left_->getEffort() + right_->getEffort();
00241     feedback.reached_goal = false;
00242     feedback.stalled = false;
00243     server_->publishFeedback(feedback);
00244 
00245     // Goal detection
00246     if (fabs(feedback.position - goal->command.position) < 0.002)
00247     {
00248       result.position = feedback.position;
00249       result.effort = feedback.effort;
00250       result.reached_goal = true;
00251       result.stalled = false;
00252       ROS_DEBUG_NAMED("ParallelGripperController", "Command Succeeded.");
00253       server_->setSucceeded(result);
00254       return;
00255     }
00256 
00257     // Stall detection
00258     if (fabs(feedback.position - last_position) > 0.005)
00259     {
00260       last_position = feedback.position;
00261       last_position_time = ros::Time::now();
00262     }
00263     else
00264     {
00265       if (ros::Time::now() - last_position_time > ros::Duration(2.0))
00266       {
00267         result.position = feedback.position;
00268         result.effort = feedback.effort;
00269         result.reached_goal = false;
00270         result.stalled = true;
00271         ROS_DEBUG_NAMED("ParallelGripperController", "Gripper stalled, but succeeding.");
00272         server_->setSucceeded(result);
00273         return;
00274       }
00275     }
00276 
00277     r.sleep();
00278   }
00279 }
00280 
00281 std::vector<std::string> ParallelGripperController::getCommandedNames()
00282 {
00283   std::vector<std::string> names;
00284   names.push_back(left_->getName());
00285   names.push_back(right_->getName());
00286   return names;
00287 }
00288 
00289 std::vector<std::string> ParallelGripperController::getClaimedNames()
00290 {
00291   // Claimed == commanded.
00292   return getCommandedNames();
00293 }
00294 
00295 }  // namespace robot_controllers


robot_controllers
Author(s): Michael Ferguson
autogenerated on Wed Jun 14 2017 04:09:10