Go to the documentation of this file.00001
00002
00003 PKG = 'webui'
00004 NAME = 'fake_motors'
00005
00006 import roslib; roslib.load_manifest(PKG)
00007
00008 import sys
00009 import time
00010
00011 import rospy
00012 from std_msgs.msg import Bool
00013 from std_srvs.srv import Empty,EmptyResponse
00014
00015 from optparse import OptionParser
00016 def talker(options):
00017 pub = rospy.Publisher("pr2_etherCAT/motors_halted", Bool)
00018 rospy.init_node(NAME, anonymous=True)
00019 while not rospy.is_shutdown():
00020 out = Bool()
00021 out.data = options.halt
00022 pub.publish(out)
00023 rospy.sleep(1.0)
00024
00025 def halt_motors(req):
00026 options.halt = True
00027 return EmptyResponse()
00028
00029 def reset_motors(req):
00030 options.halt = False
00031 return EmptyResponse()
00032
00033 if __name__ == '__main__':
00034 parser = OptionParser()
00035 parser.add_option('--halt', action="store_true", dest="halt", default=True)
00036 (options, args) = parser.parse_args()
00037 h = rospy.Service('pr2_etherCAT/halt_motors', Empty, halt_motors)
00038 r = rospy.Service('pr2_etherCAT/reset_motors', Empty, reset_motors)
00039 try:
00040 talker(options)
00041 except KeyboardInterrupt, e:
00042 pass
00043 print "exiting"
00044