fake_motors.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 PKG = 'webui' # this package name
4 NAME = 'fake_motors'
5 
6 import roslib; roslib.load_manifest(PKG)
7 
8 import sys
9 import time
10 
11 import rospy
12 from std_msgs.msg import Bool
13 from std_srvs.srv import Empty,EmptyResponse
14 
15 from optparse import OptionParser
16 def talker(options):
17  pub = rospy.Publisher("pr2_etherCAT/motors_halted", Bool)
18  rospy.init_node(NAME, anonymous=True)
19  while not rospy.is_shutdown():
20  out = Bool()
21  out.data = options.halt
22  pub.publish(out)
23  rospy.sleep(1.0)
24 
25 def halt_motors(req):
26  options.halt = True
27  return EmptyResponse()
28 
29 def reset_motors(req):
30  options.halt = False
31  return EmptyResponse()
32 
33 if __name__ == '__main__':
34  parser = OptionParser()
35  parser.add_option('--halt', action="store_true", dest="halt", default=True)
36  (options, args) = parser.parse_args()
37  h = rospy.Service('pr2_etherCAT/halt_motors', Empty, halt_motors)
38  r = rospy.Service('pr2_etherCAT/reset_motors', Empty, reset_motors)
39  try:
40  talker(options)
41  except KeyboardInterrupt, e:
42  pass
43  print "exiting"
44 
def halt_motors(req)
Definition: fake_motors.py:25
def talker(options)
Definition: fake_motors.py:16
def reset_motors(req)
Definition: fake_motors.py:29


webui
Author(s): Scott Hassan
autogenerated on Mon Jun 10 2019 15:51:24