action_executor.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 
00003 import roslib; roslib.load_manifest('shell_execution_action_server')
00004 import rospy
00005 
00006 import actionlib
00007 
00008 import shell_execution_action_server.msg
00009 import os
00010 import subprocess
00011 import StringIO
00012 
00013 class ShellCommand(object):
00014   # create messages that are used to publish feedback/result
00015   _feedback = shell_execution_action_server.msg.ShellCommandFeedback()
00016   _result   = shell_execution_action_server.msg.ShellCommandResult()
00017 
00018   def __init__(self, name):
00019     self._action_name = name
00020     self._as = actionlib.SimpleActionServer(self._action_name, shell_execution_action_server.msg.ShellCommandAction, execute_cb=self.execute_cb)
00021     self._as.start()
00022     self._feedback = shell_execution_action_server.msg.ShellCommandFeedback()
00023     
00024   def execute_cb(self, goal):
00025     
00026     # publish info to the console for the user
00027     rospy.loginfo('%s: Executing: %s' % (self._action_name, goal.command)) 
00028     #self._as.accept_new_goal()
00029     
00030     # start executing the action
00031     process = subprocess.Popen(goal.command, shell=True, stderr=subprocess.PIPE, stdout=subprocess.PIPE)
00032     r = rospy.Rate(10);
00033     ret_code = None
00034     while ret_code == None:
00035       if self._as.is_preempt_requested():
00036         rospy.logerror('%s: Preempted' % self._action_name)
00037         process.kill() 
00038         self._result.output += process.stderr.read()  
00039         self._result.output += process.stdout.read()  
00040         self._as.set_preempted()
00041         break
00042 
00043       self._feedback.stderr = process.stderr.read()  
00044       self._feedback.stdout = process.stdout.read()  
00045       self._result.stderr += self._feedback.stderr 
00046       self._result.stdout += self._feedback.stdout 
00047       self._as.publish_feedback(self._feedback)
00048       ret_code = process.poll()
00049       r.sleep()
00050 
00051     if (ret_code == 0):
00052       self._result.exit_code=0
00053       rospy.loginfo('%s: Succeeded' % self._action_name)
00054       self._as.set_succeeded(self._result)
00055     else:
00056       print "Command Failed, Exit Code: ", ret_code
00057       self._result.exit_code = ret_code
00058       rospy.loginfo('%s: Failed' % self._action_name)
00059       self._as.set_aborted(self._result)
00060 
00061       
00062 if __name__ == '__main__':
00063   rospy.init_node('shell_execution_action_server')
00064   ShellCommand(rospy.get_name())
00065   rospy.spin()
00066 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


shell_execution_action_server
Author(s): Felix Endres
autogenerated on Wed Dec 26 2012 15:43:06