navigator_io.py
Go to the documentation of this file.
00001 #!/usr/bin/python2
00002 
00003 # Copyright (c) 2013-2015, Rethink Robotics
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 # 1. Redistributions of source code must retain the above copyright notice,
00010 #    this list of conditions and the following disclaimer.
00011 # 2. Redistributions in binary form must reproduce the above copyright
00012 #    notice, this list of conditions and the following disclaimer in the
00013 #    documentation and/or other materials provided with the distribution.
00014 # 3. Neither the name of the Rethink Robotics nor the names of its
00015 #    contributors may be used to endorse or promote products derived from
00016 #    this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 import argparse
00031 import sys
00032 
00033 import rospy
00034 
00035 import baxter_interface
00036 
00037 
00038 def blink():
00039     navs = (
00040         baxter_interface.Navigator('left'),
00041         baxter_interface.Navigator('right'),
00042         baxter_interface.Navigator('torso_left'),
00043         baxter_interface.Navigator('torso_right'),)
00044 
00045     print ("Blinking LED's for 10 seconds")
00046     rate = rospy.Rate(10)
00047     i = 0
00048     while not rospy.is_shutdown() and i < 100:
00049         for nav in navs:
00050             nav.inner_led = not nav.inner_led
00051             nav.outer_led = not nav.outer_led
00052         rate.sleep()
00053         i += 1
00054 
00055 
00056 def echo_input():
00057     def b0_pressed(v):
00058         print ("Button 0: %s" % (v,))
00059 
00060     def b1_pressed(v):
00061         print ("Button 1: %s" % (v,))
00062 
00063     def b2_pressed(v):
00064         print ("Button 2: %s" % (v,))
00065 
00066     def wheel_moved(v):
00067         print ("Wheel Increment: %d, New Value: %s" % (v, nav.wheel))
00068 
00069     nav = baxter_interface.Navigator('left')
00070     nav.button0_changed.connect(b0_pressed)
00071     nav.button1_changed.connect(b1_pressed)
00072     nav.button2_changed.connect(b2_pressed)
00073     nav.wheel_changed.connect(wheel_moved)
00074 
00075     print ("Press input buttons on the left navigator, "
00076            "input will be echoed here.")
00077 
00078     rate = rospy.Rate(1)
00079     i = 0
00080     while not rospy.is_shutdown() and i < 10:
00081         rate.sleep()
00082         i += 1
00083 
00084 
00085 def main():
00086     """RSDK Navigator Input/Output Example
00087 
00088     Demonstrates Navigator output by blinking the lights, or
00089     Navigator input by echoing input values from wheels and
00090     buttons.
00091 
00092     Run this example, selecting either the input or output action
00093     with the corresponding arguments, then follow the instructions
00094     on screen.
00095 
00096     Uses the baxter_interface.Navigator class to interface with the
00097     four Navigator button/LED controls. Also shows a nice example of
00098     using the button_changed Signal feature.
00099     """
00100     arg_fmt = argparse.RawDescriptionHelpFormatter
00101     parser = argparse.ArgumentParser(formatter_class=arg_fmt,
00102                                      description=main.__doc__)
00103     action_grp = parser.add_mutually_exclusive_group(required=True)
00104     action_grp.add_argument(
00105         '-b', '--blink', dest='action', action='store_const', const=blink,
00106         help='Blink navigator lights for 10 seconds'
00107     )
00108     action_grp.add_argument(
00109         '-i', '--input', dest='action', action='store_const', const=echo_input,
00110         help='Show input of left arm for 10 seconds'
00111     )
00112     args = parser.parse_args(rospy.myargv()[1:])
00113 
00114     rospy.init_node('rsdk_navigator_io', anonymous=True)
00115     args.action()
00116     return 0
00117 
00118 if __name__ == '__main__':
00119     sys.exit(main())


baxter_examples
Author(s): Rethink Robotics Inc.
autogenerated on Thu Aug 27 2015 12:31:14