rosshellX.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import sys
00003 import os
00004 import subprocess as sp
00005 import fcntl
00006 
00007 import roslib; roslib.load_manifest("rosshell")
00008 import rospy
00009 from std_msgs.msg import String
00010 
00011 import time
00012 
00013 def callbackStdIn(msg):
00014         global process
00015 
00016         # un/comment this to enable tostopic to publish strings...
00017         msg.data = msg.data.replace("\\n", "\n")
00018 
00019         process.stdin.write(msg.data)
00020         rospy.loginfo("stdin: " +msg.data)
00021 
00022 if __name__ == "__main__":
00023 
00024         rospy.init_node('rosshellX')
00025 
00026         topicStdOut = rospy.get_param('~stdout', "/rosshellX/stdout")
00027         topicStdErr = rospy.get_param('~stderr', "/rosshellX/stderr")
00028         topicStdIn  = rospy.get_param('~stdin', "/rosshellX/stdin")
00029         cmd_user    = rospy.get_param('~command', "")
00030 
00031         #print len(cmd_user)
00032 
00033         # check if there is a command
00034         if len(cmd_user) == 0:
00035                 if len(sys.argv) >= 2:
00036                         cmd_user = sys.argv[1]
00037                 else:
00038                         rospy.logerr("no command to interprete defined, try _command:=\"command\"")
00039                         sys.exit()
00040 
00041         rospy.loginfo("execute command: " + cmd_user)
00042         rospy.loginfo("stdout on: " + topicStdOut)
00043         rospy.loginfo("stderr on:  " + topicStdErr)
00044         rospy.loginfo("stdin on:  " + topicStdIn)
00045 
00046         # change the buffer mode of the subprocess-shell to linebufferd
00047         cmd_stdbuf = "stdbuf -o L"
00048         cmd = cmd_stdbuf + " " + cmd_user
00049 
00050         process = sp.Popen(cmd.split(" "), stdout=sp.PIPE, stderr=sp.PIPE, stdin=sp.PIPE, bufsize=1)
00051         rospy.loginfo("started process with pid " + str(process.pid))
00052         rospy.loginfo("XXX")
00053 
00054         pubOUT = rospy.Publisher( topicStdOut, String, queue_size=10)
00055         pubERR = rospy.Publisher( topicStdErr, String, queue_size=10)
00056         subIN  = rospy.Subscriber(topicStdIn,  String, callbackStdIn)
00057 
00058         # putting readline of stdout and stderr into non-blocking mode
00059         fd_out = process.stdout.fileno()
00060         fl = fcntl.fcntl(fd_out, fcntl.F_GETFL)
00061         fcntl.fcntl(fd_out, fcntl.F_SETFL, fl | os.O_NONBLOCK)
00062 
00063         fd_err = process.stderr.fileno()
00064         fl = fcntl.fcntl(fd_err, fcntl.F_GETFL)
00065         fcntl.fcntl(fd_err, fcntl.F_SETFL, fl | os.O_NONBLOCK)
00066 
00067 
00068         while not rospy.is_shutdown():
00069                 try:
00070                         stdout = process.stdout.readline()
00071                         if len(stdout) > 0:
00072                                 pubOUT.publish(String(stdout))
00073                                 rospy.loginfo("stdout: " +stdout)
00074                 except Exception as e:
00075                         pass
00076 
00077                 try:
00078                         stderr = process.stderr.readline()
00079                         if len(stderr) > 0:
00080                                 pubERR.publish(String(stderr))
00081                                 rospy.logerr("stderr: " +stderr)
00082                 except Exception as e:
00083                         pass
00084 
00085                 time.sleep(0.001)
00086 
00087                 # process is terminated
00088                 #if process.poll()!=0:
00089                 #       break
00090 
00091         #process.terminate()
00092         ret = process.returncode
00093         rospy.signal_shutdown('finish')
00094         sys.exit(ret)


rosshell
Author(s):
autogenerated on Thu Jun 6 2019 21:00:37