xdisplay_image.py
Go to the documentation of this file.
00001 #!/usr/bin/python2
00002 
00003 # Copyright (c) 2013-2015, Rethink Robotics
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 # 1. Redistributions of source code must retain the above copyright notice,
00010 #    this list of conditions and the following disclaimer.
00011 # 2. Redistributions in binary form must reproduce the above copyright
00012 #    notice, this list of conditions and the following disclaimer in the
00013 #    documentation and/or other materials provided with the distribution.
00014 # 3. Neither the name of the Rethink Robotics nor the names of its
00015 #    contributors may be used to endorse or promote products derived from
00016 #    this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 import os
00031 import sys
00032 import argparse
00033 
00034 import rospy
00035 
00036 import cv2
00037 import cv_bridge
00038 
00039 from sensor_msgs.msg import (
00040     Image,
00041 )
00042 
00043 
00044 def send_image(path):
00045     """
00046     Send the image located at the specified path to the head
00047     display on Baxter.
00048 
00049     @param path: path to the image file to load and send
00050     """
00051     img = cv2.imread(path)
00052     msg = cv_bridge.CvBridge().cv2_to_imgmsg(img, encoding="bgr8")
00053     pub = rospy.Publisher('/robot/xdisplay', Image, latch=True, queue_size=1)
00054     pub.publish(msg)
00055     # Sleep to allow for image to be published.
00056     rospy.sleep(1)
00057 
00058 
00059 def main():
00060     """RSDK Xdisplay Example: Image Display
00061 
00062     Displays a given image file on Baxter's face.
00063 
00064     Pass the relative or absolute file path to an image file on your
00065     computer, and the example will read and convert the image using
00066     cv_bridge, sending it to the screen as a standard ROS Image Message.
00067     """
00068     epilog = """
00069 Notes:
00070     Max screen resolution is 1024x600.
00071     Images are always aligned to the top-left corner.
00072     Image formats are those supported by OpenCv - LoadImage().
00073     """
00074     arg_fmt = argparse.RawDescriptionHelpFormatter
00075     parser = argparse.ArgumentParser(formatter_class=arg_fmt,
00076                                      description=main.__doc__,
00077                                      epilog=epilog)
00078     required = parser.add_argument_group('required arguments')
00079     required.add_argument(
00080         '-f', '--file', metavar='PATH', required=True,
00081         help='Path to image file to send'
00082     )
00083     parser.add_argument(
00084         '-d', '--delay', metavar='SEC', type=float, default=0.0,
00085         help='Time in seconds to wait before publishing image'
00086     )
00087     args = parser.parse_args(rospy.myargv()[1:])
00088 
00089     rospy.init_node('rsdk_xdisplay_image', anonymous=True)
00090 
00091     if not os.access(args.file, os.R_OK):
00092         rospy.logerr("Cannot read file at '%s'" % (args.file,))
00093         return 1
00094 
00095     # Wait for specified time
00096     if args.delay > 0:
00097         rospy.loginfo(
00098             "Waiting for %s second(s) before publishing image to face" %
00099             (args.delay,)
00100         )
00101         rospy.sleep(args.delay)
00102 
00103     send_image(args.file)
00104     return 0
00105 
00106 if __name__ == '__main__':
00107     sys.exit(main())


baxter_examples
Author(s): Rethink Robotics Inc.
autogenerated on Thu Aug 27 2015 12:31:14