gripper_controller.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 // author: Adam Leeper
00031 
00032 #include <pr2_wrappers/gripper_controller.h>
00033 
00034 namespace pr2_wrappers {
00035 
00036 static const std::string JOINT_STATES_TOPIC = "joint_states";
00037 
00038 GripperController::GripperController() :
00039   root_nh_(""),
00040   priv_nh_("~"),
00041   gripper_action_client_("","/gripper_action", true, true)
00042 {
00043     priv_nh_.param<double>("l_gripper_open_gap_value", l_gripper_open_gap_value_, 0.086);
00044     priv_nh_.param<double>("l_gripper_closed_gap_value", l_gripper_closed_gap_value_, 0.0);
00045     priv_nh_.param<double>("l_gripper_max_effort", l_gripper_max_effort_, 50);
00046     priv_nh_.param<std::string>("l_gripper_type", l_gripper_type_, "pr2");
00047 
00048     priv_nh_.param<double>("r_gripper_open_gap_value", r_gripper_open_gap_value_, 0.086);
00049     priv_nh_.param<double>("r_gripper_closed_gap_value", r_gripper_closed_gap_value_, 0.0);
00050     priv_nh_.param<double>("r_gripper_max_effort", r_gripper_max_effort_, 50);
00051     priv_nh_.param<std::string>("r_gripper_type", r_gripper_type_, "pr2");
00052 }
00053 
00054 GripperController::~GripperController()
00055 {
00056 }
00057 
00058 std::string GripperController::virtualJointName(std::string arm_name)
00059 {
00060   if (arm_name=="right_arm") return "r_gripper_joint";
00061   return "l_gripper_joint";
00062 }
00063 
00064 bool GripperController::getGripperValue(std::string arm_name, double &value)
00065 {
00066   //get the joint states
00067   sensor_msgs::JointState::ConstPtr joint_states = 
00068     ros::topic::waitForMessage<sensor_msgs::JointState>(JOINT_STATES_TOPIC, root_nh_, ros::Duration(2.0));
00069   if (!joint_states)
00070   {
00071     ROS_ERROR("pr2 gripper grasp status: joint states not received");
00072     return false;
00073   }
00074   
00075   //find the gripper joint
00076   size_t i;
00077   std::string virtual_joint_name = virtualJointName(arm_name);
00078   for (i=0; i<joint_states->name.size(); i++)
00079   {
00080     if (joint_states->name[i] == virtual_joint_name) break;
00081   }
00082   if (i==joint_states->name.size())
00083   {
00084     ROS_ERROR("pr2_gripper grasp status: gripper joint %s not found in joint state", virtual_joint_name.c_str());
00085     return false;
00086   }
00087   if (joint_states->position.size() <= i)
00088   {
00089     ROS_ERROR("pr2_gripper grasp status: malformed joint state message received");
00090     return false;
00091   }
00092   value = joint_states->position[i];
00093     return true;
00094 }
00095 
00096 bool GripperController::commandGripperValue(std::string arm_name, double value)
00097 {
00098   pr2_controllers_msgs::Pr2GripperCommandGoal gripper_command;
00099   gripper_command.command.position = value;
00100   if (arm_name=="right_arm") gripper_command.command.max_effort = r_gripper_max_effort_;
00101   else gripper_command.command.max_effort = l_gripper_max_effort_;
00102   try
00103   {
00104     gripper_action_client_.client(arm_name).sendGoal(gripper_command);
00105   }
00106   catch(object_manipulator::ServiceNotFoundException &ex)
00107   {
00108     ROS_ERROR("Gripper action not available");
00109     return false;
00110   }
00111   return true;
00112 }
00113 
00114 }


pr2_wrappers
Author(s): Adam Leeper
autogenerated on Mon Oct 6 2014 12:08:38