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 import os
00031 import sys
00032 import argparse
00033
00034 import rospy
00035
00036 import cv
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 = cv.LoadImage(path)
00052 msg = cv_bridge.CvBridge().cv_to_imgmsg(img, encoding="bgr8")
00053 pub = rospy.Publisher('/robot/xdisplay', Image, latch=True)
00054 pub.publish(msg)
00055
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
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())