00001 /************************************************************************** 00002 ** Copyright (c) 2015 United States Government as represented by the 00003 ** National Aeronotics and Space Administration. All Rights Reserved 00004 ** 00005 ** Author: Allison Thackston 00006 ** Created: 20 Feb 2015 00007 ** 00008 ** Developed jointly by NASA/JSC and Oceaneering Space Systems 00009 ** 00010 ** Licensed under the NASA Open Source Agreement v1.3 (the "License"); 00011 ** you may not use this file except in compliance with the License. 00012 ** You may obtain a copy of the License at 00013 ** 00014 ** http://opensource.org/licenses/NASA-1.3 00015 ** 00016 ** Unless required by applicable law or agreed to in writing, software 00017 ** distributed under the License is distributed on an "AS IS" BASIS, 00018 ** WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00019 ** See the License for the specific language governing permissions and 00020 ** limitations under the License. 00021 **************************************************************************/ 00022 00023 #ifndef R2ROSGRIPPER_H 00024 #define R2ROSGRIPPER_H 00025 00026 #include <ros/ros.h> 00027 #include <r2_msgs/GripperPositionCommand.h> 00028 #include <r2_msgs/JointTrajectoryReplan.h> 00029 #include <r2_msgs/ControllerJointSettings.h> 00030 00031 class R2RosGripper 00032 { 00033 public: 00034 R2RosGripper(ros::NodeHandle& nh); 00035 00036 void configure(std::vector<std::string> names, double velocity, double acceleration); 00037 void gripperCmdCallback(const r2_msgs::GripperPositionCommand& msg); 00038 00039 private: 00040 ros::NodeHandle nh; 00041 r2_msgs::GripperPositionCommand gripperCmd; 00042 00043 ros::Subscriber gripperCmdIn; 00044 00045 ros::Publisher gripperCmdOut; 00046 ros::Publisher gripperSettingsOut; 00047 00048 double velocity; 00049 double acceleration; 00050 }; 00051 00052 #endif // R2ROSGRIPPER_H