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