cb_check.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2010, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the Willow Garage nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 ##\author Kevin Watts
36 ##\brief Prints output of PR2 counterbalance check
37 
38 PKG = 'pr2_counterbalance_check'
39 import roslib
40 roslib.load_manifest(PKG)
41 
42 import os, sys
43 import rospy
44 
45 from pr2_self_test_msgs.srv import *
46 from std_msgs.msg import Bool
47 from joint_qualification_controllers.msg import CounterbalanceTestData
48 
50 
51 from optparse import OptionParser
52 
53 def dir(turns):
54  return 'CW' if turns > 0 else 'CCW'
55 
56 SPRING_TOL = 2.0
57 BAR_TOL = 0.8
58 
59 def _check_valid(params):
60  if params.timeout_hit:
61  print >> sys.stderr, "Counterbalance controller timeout hit. Increase teh timeout and retry."
62  return False
63 
64  return True
65 
66 class CounterbalanceCheck(object):
67  def __init__(self, model_file):
68  self._motors_halted = True
69  self._data = None
70 
71  self.motors_topic = rospy.Subscriber('pr2_ethercat/motors_halted', Bool, self._motors_cb)
72  self.data_topic = rospy.Subscriber('cb_test_data', CounterbalanceTestData, self._data_callback)
73 
74  self._model_file = model_file
75 
76  self._ok = True
77 
78  @property
79  def has_data(self): return self._data is not None
80 
81  def _motors_cb(self, msg):
82  self._motors_halted = msg.data
83 
84  if self._motors_halted:
85  print >> sys.stderr, "Motors halted. Adjustment data will be invalid."
86 
87  self._ok = self._ok and not self._motors_halted
88 
89  @property
90  def ok(self): return self._ok
91 
92  def _data_callback(self, msg):
93  self._data = msg
94 
95  def process_results(self):
97  params = CounterbalanceAnalysisParams(self._data)
98 
99  if not _check_valid(params):
100  print >> sys.stderr, "Unable to calculate adjustment, invalid data"
101  return
102 
103  (secondary, cb_bar) = calc_cb_adjust(data, self._model_file)
104 
105  if (abs(secondary) > 25 or abs(cb_bar) > 25):
106  print >> sys.stderr, "Unable to calculate CB adjustment. This could mean the counterbalance is extremely out of adjustment, or your training data is invalid."
107  return
108 
109  print 'Calculated counterbalance adjustment recommendations:'
110  print '\tSecondary Spring: %.1f (%s)' % (abs(secondary), dir(secondary))
111  print '\tArm Gimbal Shaft: %.1f (%s)' % (abs(cb_bar), dir(cb_bar))
112  print 'Make sure to follow proper adjustment procedures if you choose to make an adjustment.\n'
113  print 'Your counterbalance state is up to you, these adjustments are only recommendations.\n'
114 
115 
116 if __name__ == '__main__':
117  parser = OptionParser("./cb_check.py model_file")
118  parser.add_option("-t", "--tol", action="store_true",
119  dest="tolerance", default=False,
120  help="Print recommended tolerances and exit")
121 
122  options, args = parser.parse_args(rospy.myargv())
123 
124  if options.tolerance:
125  print 'Recommended CB tolerances for secondary spring, arm gimbal shaft'
126  print '\tSecondary spring: +/-%.1f' % SPRING_TOL
127  print '\tArm Gimbal Shaft: +/-%.1f' % BAR_TOL
128  print 'If your recommended adjustment is less than this many turns, do not adjust your CB'
129  sys.exit()
130 
131  if len(args) < 2:
132  parser.error("No model file specified. Please give training data file to calculate adjustment")
133  sys.exit(2)
134 
135  if not os.path.exists(args[1]):
136  parser.error("Model file does not exist. Please give training data file to calculate adjustment")
137  sys.exit(2)
138 
139  rospy.init_node('cb_analysis')
140  app = CounterbalanceCheck(args[1])
141  try:
142  my_rate = rospy.Rate(5)
143  while app.ok and not app.has_data and not rospy.is_shutdown():
144  my_rate.sleep()
145 
146  if not app.ok:
147  print >> sys.stderr, "Unable to calculate adjustment. Check motors halted. Please retry."
148  sys.exit(2)
149 
150  if not rospy.is_shutdown():
151  app.process_results()
152  except KeyboardInterrupt, e:
153  pass
154  except Exception, e:
155  print 'Caught Exception in CB application check'
156  import traceback
157  traceback.print_exc()
def __init__(self, model_file)
Definition: cb_check.py:67
def _data_callback(self, msg)
Definition: cb_check.py:92
def dir(turns)
Definition: cb_check.py:53
def _check_valid(params)
Definition: cb_check.py:59
def calc_cb_adjust(data, model_file)
Calculates CB adjustment.
def _motors_cb(self, msg)
Definition: cb_check.py:81


pr2_counterbalance_check
Author(s): Kevin Watts
autogenerated on Wed Jan 6 2021 03:39:25