gripper_controller.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """
4  gripper_controller - action based controller for grippers.
5  Copyright (c) 2011-2014 Vanadium Labs LLC. All right reserved.
6 
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.
17 
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.
28 """
29 
30 import rospy, actionlib
31 import thread
32 
33 from control_msgs.msg import GripperCommandAction
34 from sensor_msgs.msg import JointState
35 from std_msgs.msg import Float64
36 from math import asin
37 
39  """ A simple gripper with two opposing servos to open/close non-parallel jaws. """
40 
41  def __init__(self):
42  # trapezoid model: base width connecting each gripper's rotation point
43  # + length of gripper fingers to computation point
44  # = compute angles based on a desired width at comp. point
45  self.pad_width = rospy.get_param('~pad_width', 0.01)
46  self.finger_length = rospy.get_param('~finger_length', 0.02)
47  self.min_opening = rospy.get_param('~min_opening', 0.0)
48  self.max_opening = rospy.get_param('~max_opening', 0.09)
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)
53 
54  self.left_joint = rospy.get_param('~joint_left', 'l_gripper_joint')
55  self.right_joint = rospy.get_param('~joint_right', 'r_gripper_joint')
56 
57  # publishers
58  self.l_pub = rospy.Publisher(self.left_joint+'/command', Float64, queue_size=5)
59  self.r_pub = rospy.Publisher(self.right_joint+'/command', Float64, queue_size=5)
60 
61  def setCommand(self, command):
62  # check limits
63  if command.position > self.max_opening or command.position < self.min_opening:
64  rospy.logerr("Command (%f) exceeds opening limits (%f, %f)",
65  command.position, self.max_opening, self.min_opening)
66  return False
67  # compute angles
68  angle = asin((command.position - self.pad_width)/(2*self.finger_length))
69  if self.invert_l:
70  l = -angle + self.center_l
71  else:
72  l = angle + self.center_l
73  if self.invert_r:
74  r = angle + self.center_r
75  else:
76  r = -angle + self.center_r
77  # publish msgs
78  lmsg = Float64(l)
79  rmsg = Float64(r)
80  self.l_pub.publish(lmsg)
81  self.r_pub.publish(rmsg)
82  return True
83 
84  def getPosition(self, js):
85  left = right = 0
86  for i in range(len(js.name)):
87  if js.name[i] == self.left_joint:
88  left = js.position[i]
89  elif js.name[i] == self.right_joint:
90  right = js.position[i]
91  # TODO
92 
93  return 0.0
94 
95  def getEffort(self, joint_states):
96  return 1.0
97 
99  """ One servo to open/close parallel jaws, typically via linkage. """
100 
101  def __init__(self):
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')
105 
106  # publishers
107  self.pub = rospy.Publisher(self.joint+'/command', Float64, queue_size=5)
108 
109  def setCommand(self, command):
110  self.pub.publish((command.position * self.scale) + self.center)
111 
112  def getPosition(self, joint_states):
113  return 0.0
114 
115  def getEffort(self, joint_states):
116  return 1.0
117 
118 
120  """ Simplest of grippers, one servo opens or closes to achieve a particular size opening. """
121 
122  def __init__(self):
123  self.pad_width = rospy.get_param('~pad_width', 0.01)
124  self.finger_length = rospy.get_param('~finger_length', 0.02)
125  self.min_opening = rospy.get_param('~min_opening', 0.0)
126  self.max_opening = rospy.get_param('~max_opening', 0.09)
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')
130 
131  # publishers
132  self.pub = rospy.Publisher(self.joint+'/command', Float64, queue_size=5)
133 
134  def setCommand(self, command):
135  """ Take an input command of width to open gripper. """
136  # check limits
137  if command.position > self.max_opening or command.position < self.min_opening:
138  rospy.logerr("Command (%f) exceeds opening limits (%f, %f)",
139  command.position, self.max_opening, self.min_opening)
140  return False
141  # compute angle
142  angle = asin((command.position - self.pad_width)/(2*self.finger_length))
143  # publish message
144  if self.invert:
145  self.pub.publish(-angle + self.center)
146  else:
147  self.pub.publish(angle + self.center)
148 
149  def getPosition(self, joint_states):
150  # TODO
151  return 0.0
152 
153  def getEffort(self, joint_states):
154  # TODO
155  return 1.0
156 
157 
159  """ The actual action callbacks. """
160  def __init__(self):
161  rospy.init_node('gripper_controller')
162 
163  # setup model
164  try:
165  model = rospy.get_param('~model')
166  except:
167  rospy.logerr('no model specified, exiting')
168  exit()
169  if model == 'dualservo':
171  elif model == 'parallel':
172  self.model = ParallelGripperModel()
173  elif model == 'singlesided':
174  self.model = OneSideGripperModel()
175  else:
176  rospy.logerr('unknown model specified, exiting')
177  exit()
178 
179  # subscribe to joint_states
180  rospy.Subscriber('joint_states', JointState, self.stateCb)
181 
182  # subscribe to command and then spin
183  self.server = actionlib.SimpleActionServer('~gripper_action', GripperCommandAction, execute_cb=self.actionCb, auto_start=False)
184  self.server.start()
185  rospy.spin()
186 
187  def actionCb(self, goal):
188  """ Take an input command of width to open gripper. """
189  rospy.loginfo('Gripper controller action goal recieved:%f' % goal.command.position)
190  # send command to gripper
191  self.model.setCommand(goal.command)
192  # publish feedback
193  while True:
194  if self.server.is_preempt_requested():
195  self.server.set_preemtped()
196  rospy.loginfo('Gripper Controller: Preempted.')
197  return
198  # TODO: get joint position, break when we have reached goal
199  break
200  self.server.set_succeeded()
201  rospy.loginfo('Gripper Controller: Succeeded.')
202 
203  def stateCb(self, msg):
204  self.state = msg
205 
206 if __name__=='__main__':
207  try:
208  rospy.logwarn("Please use gripper_controller (no .py)")
210  except rospy.ROSInterruptException:
211  rospy.loginfo('Hasta la Vista...')
212 


arbotix_controllers
Author(s): Michael Ferguson
autogenerated on Mon Jun 10 2019 12:43:39