enable_robot.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 os
00032 import sys
00033 
00034 import rospy
00035 
00036 import baxter_interface
00037 
00038 from baxter_interface import CHECK_VERSION
00039 
00040 
00041 def main():
00042     parser = argparse.ArgumentParser()
00043     parser.add_argument('-s', '--state', const='state',
00044                         dest='actions', action='append_const',
00045                         help='Print current robot state')
00046     parser.add_argument('-e', '--enable', const='enable',
00047                         dest='actions', action='append_const',
00048                         help='Enable the robot')
00049     parser.add_argument('-d', '--disable', const='disable',
00050                         dest='actions', action='append_const',
00051                         help='Disable the robot')
00052     parser.add_argument('-r', '--reset', const='reset',
00053                         dest='actions', action='append_const',
00054                         help='Reset the robot')
00055     parser.add_argument('-S', '--stop', const='stop',
00056                         dest='actions', action='append_const',
00057                         help='Stop the robot')
00058     args = parser.parse_args(rospy.myargv()[1:])
00059 
00060     if args.actions == None:
00061         parser.print_usage()
00062         parser.exit(0, "No action defined")
00063 
00064     rospy.init_node('rsdk_robot_enable')
00065     rs = baxter_interface.RobotEnable(CHECK_VERSION)
00066 
00067     try:
00068         for act in args.actions:
00069             if act == 'state':
00070                 print rs.state()
00071             elif act == 'enable':
00072                 rs.enable()
00073             elif act == 'disable':
00074                 rs.disable()
00075             elif act == 'reset':
00076                 rs.reset()
00077             elif act == 'stop':
00078                 rs.stop()
00079     except Exception, e:
00080         rospy.logerr(e.strerror)
00081 
00082     return 0
00083 
00084 if __name__ == '__main__':
00085     sys.exit(main())


baxter_tools
Author(s): Rethink Robotics Inc.
autogenerated on Wed Aug 26 2015 10:50:53