4 gripper_controller - action based controller for grippers. 5 Copyright (c) 2011-2014 Vanadium Labs LLC. All right reserved. 7 Redistribution and use in source and binary forms, with or without 8 modification, are permitted provided that the following conditions are met: 9 * Redistributions of source code must retain the above copyright 10 notice, this list of conditions and the following disclaimer. 11 * Redistributions in binary form must reproduce the above copyright 12 notice, this list of conditions and the following disclaimer in the 13 documentation and/or other materials provided with the distribution. 14 * Neither the name of Vanadium Labs LLC nor the names of its 15 contributors may be used to endorse or promote products derived 16 from this software without specific prior written permission. 18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 19 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 20 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 21 DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT, 22 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 23 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 24 OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 25 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE 26 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 27 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 import rospy, actionlib
33 from control_msgs.msg
import GripperCommandAction
34 from sensor_msgs.msg
import JointState
35 from std_msgs.msg
import Float64
39 """ A simple gripper with two opposing servos to open/close non-parallel jaws. """ 45 self.
pad_width = rospy.get_param(
'~pad_width', 0.01)
49 self.
center_l = rospy.get_param(
'~center_left', 0.0)
50 self.
center_r = rospy.get_param(
'~center_right', 0.0)
51 self.
invert_l = rospy.get_param(
'~invert_left',
False)
52 self.
invert_r = rospy.get_param(
'~invert_right',
False)
54 self.
left_joint = rospy.get_param(
'~joint_left',
'l_gripper_joint')
55 self.
right_joint = rospy.get_param(
'~joint_right',
'r_gripper_joint')
64 rospy.logerr(
"Command (%f) exceeds opening limits (%f, %f)",
80 self.l_pub.publish(lmsg)
81 self.r_pub.publish(rmsg)
86 for i
in range(len(js.name)):
90 right = js.position[i]
99 """ One servo to open/close parallel jaws, typically via linkage. """ 102 self.
center = rospy.get_param(
'~center', 0.0)
103 self.
scale = rospy.get_param(
'~scale', 1.0)
104 self.
joint = rospy.get_param(
'~joint',
'gripper_joint')
107 self.
pub = rospy.Publisher(self.
joint+
'/command', Float64, queue_size=5)
110 self.pub.publish((command.position * self.
scale) + self.
center)
120 """ Simplest of grippers, one servo opens or closes to achieve a particular size opening. """ 127 self.
center = rospy.get_param(
'~center', 0.0)
128 self.
invert = rospy.get_param(
'~invert',
False)
129 self.
joint = rospy.get_param(
'~joint',
'gripper_joint')
132 self.
pub = rospy.Publisher(self.
joint+
'/command', Float64, queue_size=5)
135 """ Take an input command of width to open gripper. """ 138 rospy.logerr(
"Command (%f) exceeds opening limits (%f, %f)",
145 self.pub.publish(-angle + self.
center)
147 self.pub.publish(angle + self.
center)
159 """ The actual action callbacks. """ 161 rospy.init_node(
'gripper_controller')
165 model = rospy.get_param(
'~model')
167 rospy.logerr(
'no model specified, exiting')
169 if model ==
'dualservo':
171 elif model ==
'parallel':
173 elif model ==
'singlesided':
176 rospy.logerr(
'unknown model specified, exiting')
180 rospy.Subscriber(
'joint_states', JointState, self.
stateCb)
188 """ Take an input command of width to open gripper. """ 189 rospy.loginfo(
'Gripper controller action goal recieved:%f' % goal.command.position)
191 self.model.setCommand(goal.command)
194 if self.server.is_preempt_requested():
195 self.server.set_preemtped()
196 rospy.loginfo(
'Gripper Controller: Preempted.')
200 self.server.set_succeeded()
201 rospy.loginfo(
'Gripper Controller: Succeeded.')
206 if __name__==
'__main__':
208 rospy.logwarn(
"Please use gripper_controller (no .py)")
210 except rospy.ROSInterruptException:
211 rospy.loginfo(
'Hasta la Vista...')
def getEffort(self, joint_states)
def getEffort(self, joint_states)
def setCommand(self, command)
def getPosition(self, joint_states)
def getEffort(self, joint_states)
def setCommand(self, command)
def setCommand(self, command)
def getPosition(self, js)
def getPosition(self, joint_states)