do.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of the Willow Garage nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 
00035 # Author: Wim Meeussen
00036 
00037 
00038 
00039 
00040 from __future__ import with_statement
00041 
00042 import roslib; roslib.load_manifest('application_manager')
00043 import rospy
00044 import actionlib
00045 from actionlib_msgs.msg import GoalStatus
00046 import sys
00047 import optparse
00048 from application_msgs.msg import *
00049 
00050 def main():
00051    args = sys.argv
00052    args.remove(args[0])
00053 
00054    if len(args) == 0:
00055       print 'Usage: do.py list/start/stop/kill'
00056    else:
00057       if args[0] == 'list':
00058          ac = actionlib.SimpleActionClient('application_manager/list_applications', ListApplicationsAction)
00059          ac.wait_for_server(rospy.Duration(10.0))
00060          ac.send_goal_and_wait(ListApplicationsGoal())
00061          res = ac.get_result()
00062          if len(res.application_name) == 0:
00063             print "No applications available"
00064          else:
00065             print "The following appliations are managed by the application manager:"
00066             for name, status in zip(res.application_name, res.application_status):
00067                print "  - %s (%s)"%(name, status)
00068 
00069       if args[0] == 'start':
00070          for i in range(1, len(args)):
00071             ac = actionlib.SimpleActionClient('application_manager/run_application', RunApplicationAction)
00072             ac.wait_for_server(rospy.Duration(10.0))
00073             ac.send_goal(RunApplicationGoal(application_name = args[i]))
00074             while not ac.get_state() in [GoalStatus.ACTIVE, GoalStatus.REJECTED]:
00075                rospy.sleep(0.1)
00076             if ac.get_state() == GoalStatus.ACTIVE:
00077                print "Started application %s"%args[i]
00078             else:
00079                print "Failed to start application %s"%args[i]         
00080          
00081 
00082       if args[0] == 'stop':
00083          for i in range(1, len(args)):
00084             ac = actionlib.SimpleActionClient('application_manager/stop_application', StopApplicationAction)
00085             ac.wait_for_server(rospy.Duration(10.0))
00086             ac.send_goal_and_wait(StopApplicationGoal(application_name = args[i]))
00087             if ac.get_state() == GoalStatus.SUCCEEDED:
00088                print "Killed application %s"%args[i]
00089             else:
00090                print "Failed to kill application %s"%args[i]         
00091 
00092       if args[0] == 'kill':
00093          for i in range(1, len(args)):
00094             ac = actionlib.SimpleActionClient('application_manager/kill_application', KillApplicationAction)
00095             ac.wait_for_server(rospy.Duration(10.0))
00096             ac.send_goal_and_wait(KillApplicationGoal(application_name = args[i]))
00097             if ac.get_state() == GoalStatus.SUCCEEDED:
00098                print "Killed application %s"%args[i]
00099             else:
00100                print "Failed to kill application %s"%args[i]         
00101 
00102 
00103 
00104 
00105 if __name__ == '__main__':
00106    rospy.init_node('application_manager_do')
00107    main()
00108 
00109 
00110 


application_manager
Author(s): Wim Meeussen
autogenerated on Mon Dec 2 2013 12:00:57