Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 import argparse
00031 import random
00032
00033 import rospy
00034
00035 import baxter_interface
00036
00037 from baxter_interface import CHECK_VERSION
00038
00039
00040 class Wobbler(object):
00041
00042 def __init__(self):
00043 """
00044 'Wobbles' the head
00045 """
00046 self._done = False
00047 self._head = baxter_interface.Head()
00048
00049
00050 print("Getting robot state... ")
00051 self._rs = baxter_interface.RobotEnable(CHECK_VERSION)
00052 self._init_state = self._rs.state().enabled
00053 print("Enabling robot... ")
00054 self._rs.enable()
00055 print("Running. Ctrl-c to quit")
00056
00057 def clean_shutdown(self):
00058 """
00059 Exits example cleanly by moving head to neutral position and
00060 maintaining start state
00061 """
00062 print("\nExiting example...")
00063 if self._done:
00064 self.set_neutral()
00065 if not self._init_state and self._rs.state().enabled:
00066 print("Disabling robot...")
00067 self._rs.disable()
00068
00069 def set_neutral(self):
00070 """
00071 Sets the head back into a neutral pose
00072 """
00073 self._head.set_pan(0.0)
00074
00075 def wobble(self):
00076 self.set_neutral()
00077 """
00078 Performs the wobbling
00079 """
00080 self._head.command_nod()
00081 command_rate = rospy.Rate(1)
00082 control_rate = rospy.Rate(100)
00083 start = rospy.get_time()
00084 while not rospy.is_shutdown() and (rospy.get_time() - start < 10.0):
00085 angle = random.uniform(-1.5, 1.5)
00086 while (not rospy.is_shutdown() and
00087 not (abs(self._head.pan() - angle) <=
00088 baxter_interface.HEAD_PAN_ANGLE_TOLERANCE)):
00089 self._head.set_pan(angle, speed=0.3, timeout=0)
00090 control_rate.sleep()
00091 command_rate.sleep()
00092
00093 self._done = True
00094 rospy.signal_shutdown("Example finished.")
00095
00096
00097 def main():
00098 """RSDK Head Example: Wobbler
00099
00100 Nods the head and pans side-to-side towards random angles.
00101 Demonstrates the use of the baxter_interface.Head class.
00102 """
00103 arg_fmt = argparse.RawDescriptionHelpFormatter
00104 parser = argparse.ArgumentParser(formatter_class=arg_fmt,
00105 description=main.__doc__)
00106 parser.parse_args(rospy.myargv()[1:])
00107
00108 print("Initializing node... ")
00109 rospy.init_node("rsdk_head_wobbler")
00110
00111 wobbler = Wobbler()
00112 rospy.on_shutdown(wobbler.clean_shutdown)
00113 print("Wobbling... ")
00114 wobbler.wobble()
00115 print("Done.")
00116
00117 if __name__ == '__main__':
00118 main()