parallel_single_servo_controller.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """
4  parallel_single_servo_controller.py - controls a single-servo parallel-jaw gripper
5  Copyright (c) 2011 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, tf
31 import thread
32 
33 from std_msgs.msg import Float64
34 from sensor_msgs.msg import JointState
35 from math import asin
36 
38  """ A simple controller that operates a single servo parallel jaw gripper. """
39  def __init__(self):
40  rospy.init_node("gripper_controller")
41 
42  # TODO: load calibration data. Form: opening->servo angle
43  self.calib = { 0.0000 : 1.8097, 0.0159: 1.2167, 0.0254 : 0.8997, 0.0381 : 0.4499, 0.042 : 0.1943 }
44  #self.calib = { 0.0000 : 866, 0.0159: 750, 0.0254 : 688, 0.0381 : 600, 0.042 : 550 }
45 
46  # parameters
47  self.min = rospy.get_param("~min", 0.0)
48  self.max = rospy.get_param("~max", 0.042)
49  self.center = rospy.get_param("~center", 512)
50  self.invert = rospy.get_param("~invert", False)
51 
52  # publishers
53  self.commandPub = rospy.Publisher("gripper_joint/command", Float64, queue_size=5)
55 
56  # current width of gripper
57  self.width = 0.0
58 
59  # subscribe to command and then spin
60  rospy.Subscriber("~command", Float64, self.commandCb)
61  rospy.Subscriber("joint_states", JointState, self.stateCb)
62 
63  r = rospy.Rate(15)
64  while not rospy.is_shutdown():
65  # output tf
66  self.br.sendTransform((0, -self.width/2.0, 0),
67  tf.transformations.quaternion_from_euler(0, 0, 0),
68  rospy.Time.now(),
69  "gripper_left_link",
70  "gripper_link")
71  self.br.sendTransform((0, self.width/2.0, 0),
72  tf.transformations.quaternion_from_euler(0, 0, 0),
73  rospy.Time.now(),
74  "gripper_right_link",
75  "gripper_link")
76  r.sleep()
77 
78  def getCommand(self, width):
79  """ Get servo command for an opening width. """
80  keys = self.calib.keys(); keys.sort()
81  # find end points of segment
82  low = keys[0];
83  high = keys[-1]
84  for w in keys[1:-1]:
85  if w > low and w < width:
86  low = w
87  if w < high and w > width:
88  high = w
89  # linear interpolation
90  scale = (width-low)/(high-low)
91  return ((self.calib[high]-self.calib[low])*scale) + self.calib[low]
92 
93  def getWidth(self, command):
94  """ Get opening width for a particular servo command. """
95  reverse_calib = dict()
96  for k, v in self.calib.items():
97  reverse_calib[v] = k
98  keys = reverse_calib.keys(); keys.sort()
99  # find end points of segment
100  low = keys[0]
101  high = keys[-1]
102  for c in keys[1:-1]:
103  if c > low and c < command:
104  low = c
105  if c < high and c > command:
106  high = c
107  # linear interpolation
108  scale = (command-low)/(high-low)
109  return ((reverse_calib[high]-reverse_calib[low])*scale) + reverse_calib[low]
110 
111  def commandCb(self, msg):
112  """ Take an input command of width to open gripper. """
113  # check limits
114  if msg.data > self.max or msg.data < self.min:
115  rospy.logerr("Command exceeds limits.")
116  return
117  # compute angle
118  self.commandPub.publish( Float64( self.getCommand(msg.data) ) )
119 
120  def stateCb(self, msg):
121  """ The callback that listens for joint_states. """
122  try:
123  index = msg.name.index("gripper_joint")
124  except ValueError:
125  return
126  self.width = self.getWidth(msg.position[index])
127 
128 if __name__=="__main__":
129  try:
131  except rospy.ROSInterruptException:
132  rospy.loginfo("Hasta la Vista...")
133 


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