gripper_controller.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 """
00004   gripper_controller.py - controls a gripper built of two servos
00005   Copyright (c) 2011-2013 Vanadium Labs LLC.  All right reserved.
00006 
00007   Redistribution and use in source and binary forms, with or without
00008   modification, are permitted provided that the following conditions are met:
00009       * Redistributions of source code must retain the above copyright
00010         notice, this list of conditions and the following disclaimer.
00011       * Redistributions in binary form must reproduce the above copyright
00012         notice, this list of conditions and the following disclaimer in the
00013         documentation and/or other materials provided with the distribution.
00014       * Neither the name of Vanadium Labs LLC nor the names of its 
00015         contributors may be used to endorse or promote products derived 
00016         from this software without specific prior written permission.
00017   
00018   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00019   ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020   WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021   DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT,
00022   INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00023   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00024   OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00025   LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00026   OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00027   ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 """
00029 
00030 import rospy, actionlib
00031 import thread
00032 
00033 from control_msgs.msg import GripperCommandAction
00034 from sensor_msgs.msg import JointState
00035 from std_msgs.msg import Float64
00036 from math import asin
00037 
00038 class TrapezoidGripperModel:
00039     """ A simple gripper with two opposing servos to open/close non-parallel jaws. """
00040 
00041     def __init__(self):
00042         # trapezoid model: base width connecting each gripper's rotation point
00043             #              + length of gripper fingers to computation point
00044             #              = compute angles based on a desired width at comp. point
00045         self.pad_width = rospy.get_param('~pad_width', 0.01)
00046         self.finger_length = rospy.get_param('~finger_length', 0.02)
00047 
00048         self.center_l = rospy.get_param('~center_left', 0.0)
00049         self.center_r = rospy.get_param('~center_right', 0.0)
00050         self.invert_l = rospy.get_param('~invert_left', False)
00051         self.invert_r = rospy.get_param('~invert_right', False)
00052 
00053         self.left_joint = rospy.get_param('~joint_left', 'l_gripper_joint')
00054         self.right_joint = rospy.get_param('~joint_right', 'r_gripper_joint')
00055 
00056         # publishers
00057         self.l_pub = rospy.Publisher(self.left_joint+'/command', Float64)
00058         self.r_pub = rospy.Publisher(self.right_joint+'/command', Float64)
00059 
00060     def setCommand(self, command):
00061         # check limits
00062         if command.position > self.max_opening or command.position < self.min_opening:
00063             rospy.logerr("Command exceeds limits.")
00064             return False
00065         # compute angles
00066         angle = asin((command.position - self.pad_width)/(2*self.finger_length))
00067         if self.invert_l:
00068             l = -angle + self.center_l
00069         else:
00070             l = angle + self.center_l
00071         if self.invert_r:
00072             r = angle + self.center_r
00073         else:
00074             r = -angle + self.center_r
00075         # publish msgs
00076         lmsg = Float64(l)
00077         rmsg = Float64(r)
00078         self.l_pub.publish(lmsg)
00079         self.r_pub.publish(rmsg)
00080         return True
00081 
00082     def getPosition(self, js):
00083         left = right = 0
00084         for i in range(len(js.name)):
00085             if js.name[i] == self.left_joint:
00086                 left = js.position[i]
00087             elif js.name[i] == self.right_joint:
00088                 right = js.position[i]
00089         # TODO
00090 
00091         return 0.0
00092 
00093     def getEffort(self, joint_states):
00094         return 1.0
00095 
00096 
00097 class ParallelGripperModel:
00098     """ One servo to open/close parallel jaws, typically via linkage. """
00099 
00100     def __init__(self):
00101         self.center = rospy.get_param('~center', 0.0)
00102         self.scale = rospy.get_param('~scale', 1.0)
00103         self.joint = rospy.get_param('~joint', 'gripper_joint')
00104 
00105         # publishers
00106         self.pub = rospy.Publisher(self.joint+'/command', Float64)
00107 
00108     def setCommand(self, command):
00109         self.pub.publish((command.position * self.scale) + self.center)
00110 
00111     def getPosition(self, joint_states):
00112         return 0.0
00113 
00114     def getEffort(self, joint_states):
00115         return 1.0
00116 
00117 class OneSideGripperModel:
00118     """ Simplest of grippers, one servo opens or closes to achieve a particular size opening. """
00119 
00120     def __init__(self):
00121         self.pad_width = rospy.get_param('~pad_width', 0.01)
00122         self.finger_length = rospy.get_param('~finger_length', 0.02)
00123         self.center = rospy.get_param('~center', 0.0)
00124         self.invert = rospy.get_param('~invert', False)
00125         self.joint = rospy.get_param('~joint', 'gripper_joint')
00126 
00127         # publishers
00128         self.pub = rospy.Publisher(self.joint+'/command', Float64)
00129 
00130     def setCommand(self, command):
00131         """ Take an input command of width to open gripper. """
00132         # compute angle
00133         angle = asin((command.position - self.pad_width)/(2*self.finger_length))
00134         # publish message
00135         if self.invert:
00136             self.pub.publish(-angle + self.center)
00137         else:
00138             self.pub.publish(angle + self.center)
00139 
00140     def getPosition(self, joint_states):
00141         # TODO
00142         return 0.0
00143 
00144     def getEffort(self, joint_states):
00145         # TODO
00146         return 1.0
00147 
00148 
00149 class GripperActionController:
00150     """ The actual action callbacks. """
00151     def __init__(self):
00152         rospy.init_node('gripper_controller')
00153 
00154         # setup model
00155         try:
00156             model = rospy.get_param('~model')
00157         except:
00158             rospy.logerr('no model specified, exiting')
00159             exit()
00160         if model == 'dualservo':
00161             self.model = TrapezoidGripperModel()
00162         elif model == 'parallel':
00163             self.model = ParallelGripperModel()
00164         elif model == 'singlesided':
00165             self.model = OneSideGripperModel()
00166         else:
00167             rospy.logerr('unknown model specified, exiting')
00168             exit()
00169 
00170         # standard params
00171         self.min_opening = rospy.get_param('~min', 0.0)
00172         self.max_opening = rospy.get_param('~max', 0.09)
00173 
00174         # subscribe to joint_states
00175         rospy.Subscriber('joint_states', JointState, self.stateCb)
00176 
00177         # subscribe to command and then spin
00178         self.server = actionlib.SimpleActionServer('~gripper_action', GripperCommandAction, execute_cb=self.actionCb, auto_start=False)
00179         self.server.start()
00180         rospy.spin()
00181 
00182     def actionCb(self, goal):
00183         """ Take an input command of width to open gripper. """
00184         rospy.loginfo('Gripper controller action goal recieved:%f' % goal.command.position)
00185         # send command to gripper
00186         self.model.setCommand(goal.command)
00187         # publish feedback
00188         while True:
00189             if self.server.is_preempt_requested():
00190                 self.server.set_preemtped()
00191                 rospy.loginfo('Gripper Controller: Preempted.')
00192                 return
00193             # TODO: get joint position, break when we have reached goal
00194             break
00195         self.server.set_succeeded()
00196         rospy.loginfo('Gripper Controller: Succeeded.')
00197 
00198     def stateCb(self, msg):
00199         self.state = msg
00200 
00201 if __name__=='__main__': 
00202     try:
00203         GripperActionController()
00204     except rospy.ROSInterruptException:
00205         rospy.loginfo('Hasta la Vista...')
00206         


arbotix_controllers
Author(s): Michael Ferguson
autogenerated on Sun Oct 5 2014 22:16:07