mimic_node.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 import os
00018 import vlc
00019 import threading
00020 
00021 import roslib
00022 import rospy
00023 import actionlib
00024 
00025 from cob_mimic.srv import *
00026 from cob_mimic.msg import *
00027 
00028 class Mimic:
00029   def service_cb(self, req):
00030       success = self.set_mimic(req.mimic, req.speed, req.repeat)
00031       return SetMimicResponse(success, "")
00032 
00033   def action_cb(self, goal):
00034       if self.set_mimic(goal.mimic, goal.speed, goal.repeat):
00035         self._as.set_succeeded()
00036       else:
00037         self._as.set_aborted()
00038 
00039   def set_mimic(self, mimic, speed, repeat):
00040       rospy.loginfo("Mimic: %s", mimic)
00041       file_location = '/tmp/mimic/' + mimic + '.mp4'
00042       if(not os.path.isfile(file_location)):
00043         rospy.logerror("File not found: %s", file_location)
00044         return False
00045 
00046       # repeat cannot be 0
00047       repeat = max (1, repeat)
00048 
00049       for i in range(0, repeat):
00050         rospy.loginfo("Repeat: %s, Mimic: %s", repeat, mimic)
00051         command = "export DISPLAY=:0 && vlc --video-wallpaper --video-filter 'rotate{angle=%d}' --vout glx --one-instance --playlist-enqueue --no-video-title-show --rate %f  %s  vlc://quit"  % (self.rotation, speed, file_location)
00052         os.system(command)
00053 
00054       return True
00055 
00056   def defaultMimic(self):
00057     file_location = '/tmp/mimic/' + self.default_mimic + '.mp4'
00058     if not os.path.isfile(file_location):
00059       rospy.logerror("File not found: %s", file_location)
00060       return
00061 
00062     while not rospy.is_shutdown():
00063       command = "export DISPLAY=:0 && vlc --video-wallpaper --video-filter 'rotate{angle=%d}' --vout glx --loop --one-instance --playlist-enqueue --no-video-title-show --rate %f  %s  vlc://quit"  % (self.rotation, self.default_speed, file_location)
00064       os.system(command)
00065 
00066   def main(self):
00067     self.default_speed = 1.0
00068     self.default_mimic = "default"
00069     self.rotation = rospy.get_param('~rotation', 0)
00070 
00071     # copy all videos to /tmp
00072     rospy.loginfo("copying all mimic files to /tmp/mimic...")
00073     file_location = roslib.packages.get_pkg_dir('cob_mimic') + '/common/*.mp4'
00074     os.system("mkdir -p /tmp/mimic")
00075     os.system("cp " + file_location + " /tmp/mimic")
00076     rospy.loginfo("...copied all mimic files to /tmp/mimic")
00077 
00078     self._ss = rospy.Service('~set_mimic', SetMimic, self.service_cb)
00079     self._as = actionlib.SimpleActionServer('~set_mimic', cob_mimic.msg.SetMimicAction, execute_cb=self.action_cb, auto_start = False)
00080     self._as.start()
00081 
00082     rospy.spin()
00083 
00084 
00085 
00086 if __name__ == "__main__":
00087   rospy.init_node('mimic')
00088   try:
00089     mimic = Mimic()
00090     mimic.main()
00091   except (rospy.ROSInterruptException, KeyboardInterrupt, SystemExit) as e:
00092     rospy.loginfo('Exiting: ' + str(e))
00093     pass
00094 


cob_mimic
Author(s): Nadia Hammoudeh Garcia , Benjamin Maidel
autogenerated on Sat Jun 8 2019 21:02:12