00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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
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
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 = 10000;
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 }