parallel_gripper_action_controller.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 """
00004   parallel_gripper_controller.py - controls a gripper built of two servos
00005   Copyright (c) 2011 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 std_msgs.msg import Float64
00035 from math import asin
00036 
00037 class ParallelGripperActionController:
00038     """ A simple controller that operates two opposing servos to
00039         open/close to a particular size opening. """
00040     def __init__(self):
00041         rospy.init_node('gripper_controller')
00042         rospy.logwarn("parallel_gripper_action_controller.py is deprecated and will be removed in ROS Indigo, please use gripper_controller")
00043 
00044         # trapezoid model: base width connecting each gripper's rotation point
00045             #              + length of gripper fingers to computation point
00046             #              = compute angles based on a desired width at comp. point
00047         self.pad_width = rospy.get_param('~pad_width', 0.01)
00048         self.finger_length = rospy.get_param('~finger_length', 0.02)
00049         self.min_opening = rospy.get_param('~min', 0.0)
00050         self.max_opening = rospy.get_param('~max', 2*self.finger_length)
00051 
00052         self.center_l = rospy.get_param('~center_left', 0.0)
00053         self.center_r = rospy.get_param('~center_right', 0.0)
00054         self.invert_l = rospy.get_param('~invert_left', False)
00055         self.invert_r = rospy.get_param('~invert_right', False)
00056 
00057         # publishers
00058         self.l_pub = rospy.Publisher('l_gripper_joint/command', Float64)
00059         self.r_pub = rospy.Publisher('r_gripper_joint/command', Float64)
00060 
00061         # subscribe to command and then spin
00062         self.server = actionlib.SimpleActionServer('~gripper_action', GripperCommandAction, execute_cb=self.actionCb, auto_start=False)
00063         self.server.start()
00064         rospy.spin()
00065 
00066     def actionCb(self, goal):
00067         """ Take an input command of width to open gripper. """
00068         rospy.loginfo('Gripper controller action goal recieved:%f' % goal.command.position)
00069         command = goal.command.position
00070         # check limits
00071         if command > self.max_opening:
00072             command = self.max_opening
00073         if command < self.min_opening:
00074             command = self.min_opening
00075         # compute angles
00076         angle = asin((command - self.pad_width)/(2*self.finger_length))
00077         if self.invert_l:
00078             l = -angle + self.center_l
00079         else:
00080             l = angle + self.center_l
00081         if self.invert_r:
00082             r = angle + self.center_r
00083         else:
00084             r = -angle + self.center_r
00085         # publish msgs
00086         lmsg = Float64(l)
00087         rmsg = Float64(r)
00088         self.l_pub.publish(lmsg)
00089         self.r_pub.publish(rmsg)
00090         rospy.sleep(5.0)
00091         self.server.set_succeeded()
00092         rospy.loginfo('Gripper Controller: Done.')
00093 
00094 if __name__=='__main__': 
00095     try:
00096         ParallelGripperActionController()
00097     except rospy.ROSInterruptException:
00098         rospy.loginfo('Hasta la Vista...')
00099         


arbotix_controllers
Author(s): Michael Ferguson
autogenerated on Wed Aug 26 2015 10:44:22