Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import rospy
00036 import roslib; roslib.load_manifest('rsync_ros')
00037 import actionlib
00038 import os
00039 from rsync import Rsync
00040 from rsync_ros.msg import RsyncAction, RsyncResult, RsyncFeedback
00041
00042 class RsyncActionServer:
00043
00044 def __init__(self, name):
00045 self._action_name = name
00046 self.server = actionlib.SimpleActionServer(self._action_name, RsyncAction, self.execute, False)
00047 self.server.start()
00048 rospy.loginfo("Ready to sync files.")
00049
00050 def progress_update_cb(self, line, percent_complete, transfer_rate):
00051
00052
00053
00054 self.feedback.percent_complete = percent_complete
00055 self.feedback.transfer_rate = transfer_rate
00056 self.server.publish_feedback(self.feedback)
00057
00058 if line:
00059 rospy.loginfo(line)
00060
00061
00062 if self.server.is_preempt_requested():
00063
00064 pid = self.rsync.p.pid
00065 self.rsync.p.terminate()
00066
00067
00068 try:
00069 os.kill(pid, 0)
00070 self.rsync.p.kill()
00071 print "Forced kill"
00072 except OSError, e:
00073 print "Terminated gracefully"
00074
00075
00076 rospy.loginfo('%s: Preempted' % self._action_name)
00077 self.server.set_preempted()
00078
00079 def execute(self, goal):
00080 self.result = RsyncResult()
00081 self.feedback = RsyncFeedback()
00082
00083 rospy.loginfo("Executing rsync command '%s %s %s'", 'rsync ' + ' '.join(goal.rsync_args) + ' --progress --outbuf=L', goal.source_path, goal.destination_path)
00084
00085 self.rsync = Rsync(goal.rsync_args, goal.source_path, goal.destination_path, progress_callback=self.progress_update_cb)
00086
00087 self.result.sync_success = self.rsync.sync()
00088
00089 if not self.server.is_preempt_requested():
00090
00091 if self.rsync.stderr_block:
00092 rospy.logerr('\n{}'.format(self.rsync.stderr_block))
00093
00094 rospy.loginfo("Rsync command result '%s'", self.result.sync_success)
00095 self.server.set_succeeded(self.result)
00096
00097 if __name__ == "__main__":
00098 try:
00099 rospy.init_node('rsync_ros')
00100 RsyncActionServer(rospy.get_name())
00101 rospy.spin()
00102 except rospy.ROSInterruptException:
00103 pass