38 PKG = 
'pr2_counterbalance_check'    40 roslib.load_manifest(PKG)
    46 from std_msgs.msg 
import Bool
    47 from joint_qualification_controllers.msg 
import CounterbalanceTestData
    51 from optparse 
import OptionParser
    54     return 'CW' if turns > 0 
else 'CCW'    60     if params.timeout_hit:
    61         print >> sys.stderr, 
"Counterbalance controller timeout hit. Increase teh timeout and retry."    79     def has_data(self): 
return self._data 
is not None    85             print >> sys.stderr, 
"Motors halted. Adjustment data will be invalid."    90     def ok(self): 
return self._ok
   100             print >> sys.stderr, 
"Unable to calculate adjustment, invalid data"   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."   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'   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")
   122     options, args = parser.parse_args(rospy.myargv())
   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'   132         parser.error(
"No model file specified. Please give training data file to calculate adjustment")
   135     if not os.path.exists(args[1]):
   136         parser.error(
"Model file does not exist. Please give training data file to calculate adjustment")
   139     rospy.init_node(
'cb_analysis')
   142         my_rate = rospy.Rate(5)
   143         while app.ok 
and not app.has_data 
and not rospy.is_shutdown():
   147             print >> sys.stderr, 
"Unable to calculate adjustment. Check motors halted. Please retry."   150         if not rospy.is_shutdown():
   151             app.process_results()
   152     except KeyboardInterrupt, e:
   155         print 'Caught Exception in CB application check'   157         traceback.print_exc()
 
def __init__(self, model_file)
Stores parameters from CB analysis test. 
def _data_callback(self, msg)
def process_results(self)
def calc_cb_adjust(data, model_file)
Calculates CB adjustment. 
def _motors_cb(self, msg)