pr2_gripper_grasp_controller.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 *  Copyright (c) 2009, Willow Garage, Inc.
00004 *  All rights reserved.
00005 *
00006 *  Redistribution and use in source and binary forms, with or without
00007 *  modification, are permitted provided that the following conditions
00008 *  are met:
00009 *
00010 *   * Redistributions of source code must retain the above copyright
00011 *     notice, this list of conditions and the following disclaimer.
00012 *   * Redistributions in binary form must reproduce the above
00013 *     copyright notice, this list of conditions and the following
00014 *     disclaimer in the documentation and/or other materials provided
00015 *     with the distribution.
00016 *   * Neither the name of the Willow Garage nor the names of its
00017 *     contributors may be used to endorse or promote products derived
00018 *     from this software without specific prior written permission.
00019 *
00020 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 *  POSSIBILITY OF SUCH DAMAGE.
00032 *********************************************************************/
00033 
00034 #include <ros/ros.h>
00035 
00036 #include <actionlib/server/simple_action_server.h>
00037 #include <actionlib/client/simple_action_client.h>
00038 
00039 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
00040 
00041 #include <sensor_msgs/JointState.h>
00042 
00043 #include <object_manipulation_msgs/GraspHandPostureExecutionAction.h>
00044 #include <object_manipulation_msgs/GraspStatus.h>
00045 
00046 static const std::string JOINT_STATES_TOPIC = "joint_states";
00047 
00049 
00054 class PR2GripperGraspController
00055 {
00056 private:
00057 
00059   ros::NodeHandle root_nh_;
00060 
00062   ros::NodeHandle priv_nh_;
00063 
00065   actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> *gripper_action_client_;
00066 
00068   actionlib::SimpleActionServer<object_manipulation_msgs::GraspHandPostureExecutionAction> *action_server_;
00069 
00071   ros::ServiceServer query_srv_;
00072 
00074   std::string gripper_virtual_joint_name_;
00075 
00076   //-------------------------------- Constants ---------------------------------
00077 
00079   double gripper_open_gap_value_;
00081   static const double DEFAULT_GRIPPER_OPEN;
00082 
00084   double gripper_closed_gap_value_;
00086   static const double DEFAULT_GRIPPER_CLOSED;
00087 
00089   double gripper_object_presence_threshold_;  
00091   static const double DEFAULT_GRIPPER_OBJECT_PRESENCE_THRESHOLD;
00092 
00094   double gripper_max_effort_;
00096   static const double DEFAULT_GRIPPER_MAX_EFFORT;
00097 
00099   std::string gripper_type_;
00100 
00101   //------------------------------ Functionality -------------------------------
00102 
00104   bool getGripperValue(double &value)
00105   {
00106     //get the joint states
00107     sensor_msgs::JointState::ConstPtr joint_states = 
00108       ros::topic::waitForMessage<sensor_msgs::JointState>(JOINT_STATES_TOPIC, root_nh_);
00109     if (!joint_states)
00110     {
00111       ROS_ERROR("pr2 gripper grasp status: joint states not received");
00112       return false;
00113     }
00114     
00115     //find the gripper joint
00116     size_t i;
00117     for (i=0; i<joint_states->name.size(); i++)
00118     {
00119       if (joint_states->name[i] == gripper_virtual_joint_name_) break;
00120     }
00121     if (i==joint_states->name.size())
00122     {
00123       ROS_ERROR("pr2_gripper grasp status: gripper joint %s not found in joint state", 
00124                 gripper_virtual_joint_name_.c_str());
00125       return false;
00126     }
00127     if (joint_states->position.size() <= i)
00128     {
00129       ROS_ERROR("pr2_gripper grasp status: malformed joint state message received");
00130       return false;
00131     }
00132     value = joint_states->position[i];
00133     return true;
00134   }
00135 
00137 
00138   double jointToGap(double jointValue)
00139   {
00140     if (gripper_type_ == "pr2") return jointValue / 0.5 * 0.0857;
00141     else if (gripper_type_ == "lcg") return 2.0 * ( cos(jointValue)*60.0 + 17.5 - 6.0 ) * 1.0e-3;
00142     else {ROS_ERROR_STREAM("pr2_gripper_grasp_controller: unknown gripper type: " << gripper_type_); return 0.0;}
00143   }
00144 
00145   void executeCB(const object_manipulation_msgs::GraspHandPostureExecutionGoalConstPtr &goal)
00146   {
00147     //prepare the gripper command based on the goal
00148     pr2_controllers_msgs::Pr2GripperCommandGoal gripper_command;
00149     switch (goal->goal)
00150     {
00151     case object_manipulation_msgs::GraspHandPostureExecutionGoal::GRASP:
00152       if (goal->grasp.grasp_posture.position.empty())
00153       {
00154         ROS_ERROR("pr2 gripper grasp execution: position vector empty in requested grasp");
00155         action_server_->setAborted();
00156         return;
00157       }
00158       gripper_command.command.position = gripper_closed_gap_value_;
00159       //gripper_command.command.position = jointToGap( goal->grasp.grasp_posture.position[0] );
00160       if (goal->grasp.grasp_posture.effort.empty())
00161       {
00162         if(goal->max_contact_force > 0)
00163         {
00164           ROS_INFO("limiting max contact force to %f", goal->max_contact_force);
00165           gripper_command.command.max_effort = goal->max_contact_force;
00166         }
00167         else gripper_command.command.max_effort = gripper_max_effort_;
00168         ROS_WARN("pr2 gripper grasp execution: effort vector empty in requested grasp, using max force");
00169         //action_server_->setAborted();
00170         //return;
00171       }
00172       //we use the effort in the first joint for going to the grasp
00173       else 
00174       {
00175         if(goal->grasp.grasp_posture.effort.at(0) < goal->max_contact_force || goal->max_contact_force == 0)
00176           gripper_command.command.max_effort = goal->grasp.grasp_posture.effort.at(0);
00177         else gripper_command.command.max_effort = goal->max_contact_force;
00178       }
00179       break;
00180     case object_manipulation_msgs::GraspHandPostureExecutionGoal::PRE_GRASP:
00181       if (goal->grasp.pre_grasp_posture.position.empty())
00182       {
00183         ROS_ERROR("pr2 gripper grasp execution: position vector empty in requested pre_grasp");
00184         action_server_->setAborted();
00185         return;
00186       }
00187       //gripper_command.command.position = GRIPPER_OPEN;
00188       gripper_command.command.position = jointToGap( goal->grasp.pre_grasp_posture.position.at(0) );
00189       ROS_DEBUG("pre grasp posture opening is %.3f", gripper_command.command.position);
00190       if (goal->grasp.pre_grasp_posture.effort.empty())
00191       {
00192         gripper_command.command.max_effort = gripper_max_effort_;
00193         ROS_WARN("pr2 gripper grasp execution: effort vector empty in requested pre_grasp, using max");
00194       }
00195       else 
00196       {
00197         gripper_command.command.max_effort = goal->grasp.pre_grasp_posture.effort.at(0);
00198       }
00199       break;      
00200     case object_manipulation_msgs::GraspHandPostureExecutionGoal::RELEASE:
00201       gripper_command.command.position = gripper_open_gap_value_;
00202       gripper_command.command.max_effort = gripper_max_effort_;
00203       break;
00204     default:
00205       ROS_ERROR("pr2 gripper grasp execution: unknown goal code (%d)", goal->goal);
00206       action_server_->setAborted();
00207       return;
00208     }
00209 
00210     //check the requested effort
00211     if (gripper_command.command.max_effort > gripper_max_effort_)
00212     {
00213       ROS_WARN("pr2 gripper grasp execution: effort exceeds max value for gripper, reducing to max");
00214       gripper_command.command.max_effort = gripper_max_effort_;
00215     }
00216 
00217     //send the command to the gripper
00218     gripper_action_client_->sendGoal(gripper_command);
00219     gripper_action_client_->waitForResult();
00220 
00221     //process the result
00222     if(gripper_action_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED) 
00223     {
00224       ROS_INFO("Gripper goal achieved");
00225       action_server_->setSucceeded();
00226     } 
00227     else 
00228     {
00229       if (goal->goal == object_manipulation_msgs::GraspHandPostureExecutionGoal::GRASP)
00230       {
00231         //this is probably correct behavior, since there is an object in the gripper
00232         //we can not expect to reach our goal
00233         action_server_->setSucceeded();
00234       }
00235       else
00236       {
00237         ROS_WARN("Gripper goal not achieved for pre-grasp or release");
00238         //this might become a failure later, for now we're still investigating
00239         action_server_->setSucceeded();
00240       }
00241     }
00242   }
00243 
00244   bool serviceCallback(object_manipulation_msgs::GraspStatus::Request &request,
00245                        object_manipulation_msgs::GraspStatus::Response &response)
00246   {
00247     double gripper_value;
00248     if (!getGripperValue(gripper_value)) return false;    
00249 
00250     double min_gripper_opening = gripper_object_presence_threshold_;
00251     if (gripper_value < min_gripper_opening) 
00252     {
00253       ROS_INFO("Gripper grasp query false: gripper value %f below threshold %f", 
00254                gripper_value, min_gripper_opening);
00255       response.is_hand_occupied = false;
00256     }
00257     else 
00258     {
00259       ROS_DEBUG("Gripper grasp query true: gripper value %f above threshold %f", 
00260                gripper_value, min_gripper_opening);
00261       response.is_hand_occupied = true;
00262     }
00263     return true;
00264   }
00265                        
00266 
00267 public:
00268   PR2GripperGraspController() :
00269     root_nh_(""),
00270     priv_nh_("~")
00271   {
00272     std::string gripper_action_name = root_nh_.resolveName("gripper_action_name");
00273     gripper_action_client_ = new actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction>
00274       (gripper_action_name, true);
00275     while(!gripper_action_client_->waitForServer(ros::Duration(2.0)) && root_nh_.ok())
00276     {
00277       ROS_INFO_STREAM("Waiting for gripper action client on topic " << gripper_action_name);
00278     }
00279     if (!root_nh_.ok()) exit(0);
00280     ROS_INFO_STREAM("Using gripper action client on topic " << gripper_action_name);
00281 
00282     priv_nh_.param<std::string>("gripper_virtual_joint_name", gripper_virtual_joint_name_, "undefined");
00283     if ( gripper_virtual_joint_name_ == "undefined" )
00284     {
00285       ROS_ERROR("Gripper virtual joint name not defined; set the parameter "
00286                 "gripper_virtual_joint_name in the launch file");
00287       exit(0);
00288     }
00289 
00290     priv_nh_.param<double>("gripper_object_presence_threshold", gripper_object_presence_threshold_,
00291                            DEFAULT_GRIPPER_OBJECT_PRESENCE_THRESHOLD);
00292     priv_nh_.param<double>("gripper_open_gap_value", gripper_open_gap_value_, DEFAULT_GRIPPER_OPEN);
00293     priv_nh_.param<double>("gripper_closed_gap_value", gripper_closed_gap_value_, DEFAULT_GRIPPER_CLOSED);
00294     priv_nh_.param<double>("gripper_max_effort", gripper_max_effort_, DEFAULT_GRIPPER_MAX_EFFORT);
00295     priv_nh_.param<std::string>("gripper_type", gripper_type_, "pr2");
00296 
00297     std::string query_service_name = root_nh_.resolveName("grasp_query_name");   
00298     query_srv_ = root_nh_.advertiseService(query_service_name, &PR2GripperGraspController::serviceCallback, this);    
00299     ROS_INFO_STREAM("pr2_gripper grasp query service started on topic " << query_service_name);
00300 
00301     std::string posture_action_name = root_nh_.resolveName("posture_action_name");
00302     action_server_ = new actionlib::SimpleActionServer<object_manipulation_msgs::GraspHandPostureExecutionAction>
00303       (root_nh_, posture_action_name, boost::bind(&PR2GripperGraspController::executeCB, this, _1), false);
00304     action_server_->start();
00305     ROS_INFO_STREAM("pr2_gripper grasp hand posture action server started on topic " << posture_action_name);
00306   }
00307 
00308   ~PR2GripperGraspController()
00309   {
00310     delete action_server_;
00311     delete gripper_action_client_;
00312   }
00313 
00314 };
00315 
00316 //Note that all these values are set for the PR2 gripper
00317 const double PR2GripperGraspController::DEFAULT_GRIPPER_OPEN = 0.086;
00318 const double PR2GripperGraspController::DEFAULT_GRIPPER_CLOSED = 0.0;
00319 const double PR2GripperGraspController::DEFAULT_GRIPPER_OBJECT_PRESENCE_THRESHOLD = 0.0021;
00320 const double PR2GripperGraspController::DEFAULT_GRIPPER_MAX_EFFORT = 100;
00321 
00322 int main(int argc, char **argv)
00323 {
00324   ros::init(argc, argv, "pr2_gripper_grasp_controller");
00325   PR2GripperGraspController node;
00326   ros::spin();
00327   return 0;  
00328 }


pr2_gripper_grasp_controller
Author(s): Matei Ciocarlie
autogenerated on Fri Jan 3 2014 11:52:24