parallel_gripper_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
00031 import thread
00032 
00033 from std_msgs.msg import Float64
00034 from math import asin
00035 
00036 class ParallelGripperController:
00037     """ A simple controller that operates two opposing servos to
00038         open/close to a particular size opening. """
00039     def __init__(self):
00040         rospy.init_node("parallel_gripper_controller")
00041         rospy.logwarn("parallel_gripper_controller.py is deprecated and will be removed in ROS Indigo, please use gripper_controller")
00042 
00043         # trapezoid model: base width connecting each gripper's rotation point
00044             #              + length of gripper fingers to computation point
00045             #              = compute angles based on a desired width at comp. point
00046         self.pad_width = rospy.get_param("~pad_width", 0.01)
00047         self.finger_length = rospy.get_param("~finger_length", 0.02)
00048         self.min_opening = rospy.get_param("~min", 0.0)
00049         self.max_opening = rospy.get_param("~max", 2*self.finger_length)
00050 
00051         self.center_l = rospy.get_param("~center_left", 0.0)
00052         self.center_r = rospy.get_param("~center_right", 0.0)
00053         self.invert_l = rospy.get_param("~invert_left", False)
00054         self.invert_r = rospy.get_param("~invert_right", False)
00055 
00056         # publishers
00057         self.l_pub = rospy.Publisher("l_gripper_joint/command", Float64, queue_size=5)
00058         self.r_pub = rospy.Publisher("r_gripper_joint/command", Float64, queue_size=5)
00059 
00060         # subscribe to command and then spin
00061         rospy.Subscriber("~command", Float64, self.commandCb)
00062         rospy.spin()
00063 
00064     def commandCb(self, msg):
00065         """ Take an input command of width to open gripper. """
00066         # check limits
00067         if msg.data > self.max_opening or msg.data < self.min_opening:
00068             rospy.logerr("Command exceeds limits.")
00069             return
00070         # compute angles
00071         angle = asin((msg.data - self.pad_width)/(2*self.finger_length))
00072         if self.invert_l:
00073             l = -angle + self.center_l
00074         else:
00075             l = angle + self.center_l
00076         if self.invert_r:
00077             r = angle + self.center_r
00078         else:
00079             r = -angle + self.center_r
00080         # publish msgs
00081         lmsg = Float64(l)
00082         rmsg = Float64(r)
00083         self.l_pub.publish(lmsg)
00084         self.r_pub.publish(rmsg)
00085 
00086 if __name__=="__main__": 
00087     try:
00088         ParallelGripperController()
00089     except rospy.ROSInterruptException:
00090         rospy.loginfo("Hasta la Vista...")
00091         


arbotix_controllers
Author(s): Michael Ferguson
autogenerated on Sat Jun 8 2019 19:34:57