Introduction
This example demonstrates the usage of the xdisplay topic to publish images on Baxter's face. The main()
function records the absolute/relative path of the image to be published on Baxter's face and invokes the send_image()
function. This function reads the image and publishes it to the display topic.
Topic - /robot/xdisplay
Code Walkthrough
Now, let's break down the code
30 import os
31 import sys
32 import argparse
33
34 import rospy
35
36 import cv2
37 import cv_bridge
38
39 from sensor_msgs.msg import (
40 Image,
41 )
The cv2
library is imported to read images as cv2 messages and perform various processing on it. cv_bridge
is used to convert between OpenCV and ROS images.
44 def send_image(path):
45 """
46 Send the image located at the specified path to the head
47 display on Baxter.
48
49 @param path: path to the image file to load and send
50 """
51 img = cv2.imread(path)
The imread()
is an OpenCV function that is used to load images as 2D numpy arrays. It is important to read the images as 2D numpy arrays in OpenCV 2.0 in order to execute various OpenCV algorithms on them.
52 msg = cv_bridge.CvBridge().cv2_to_imgmsg(img, encoding="bgr8")
The OpenCV image has to be converted into ROS image message in order to send them as ROS messages or perform any ROS functions on it. The cv_bridge is used to convert between ROS and OpenCV images. cv2_to_imgmsg
converts the OpenCV image to ROS image.
53 pub = rospy.Publisher('/robot/xdisplay', Image, latch=True)
54 pub.publish(msg)
55 # Sleep to allow for image to be published.
56 rospy.sleep(1)
The Ros image is published to the /robot/xdisplay
topic.
59 def main():
60 """RSDK Xdisplay Example: Image Display
61
62 Displays a given image file on Baxter's face.
63
64 Pass the relative or absolute file path to an image file on your
65 computer, and the example will read and convert the image using
66 cv_bridge, sending it to the screen as a standard ROS Image Message.
67 """
68 epilog = """
69 Notes:
70 Max screen resolution is 1024x600.
71 Images are always aligned to the top-left corner.
72 Image formats are those supported by OpenCv - LoadImage().
73 """
74 arg_fmt = argparse.RawDescriptionHelpFormatter
75 parser = argparse.ArgumentParser(formatter_class=arg_fmt,
76 description=main.__doc__,
77 epilog=epilog)
78 required = parser.add_argument_group('required arguments')
79 required.add_argument(
80 '-f', '--file', metavar='PATH', required=True,
81 help='Path to image file to send'
82 )
83 parser.add_argument(
84 '-d', '--delay', metavar='SEC', type=float, default=0.0,
85 help='Time in seconds to wait before publishing image'
86 )
87 args = parser.parse_args(rospy.myargv()[1:])
The path of the image to be loaded, and the delay in publishing the images are captured as user arguments.
89 rospy.init_node('rsdk_xdisplay_image', anonymous=True)
90
91 if not os.access(args.file, os.R_OK):
92 rospy.logerr("Cannot read file at '%s'" % (args.file,))
93 return 1
The rospy node is initialized. Then the readability of the path entered by the user is verified.
96 if args.delay > 0:
97 rospy.loginfo(
98 "Waiting for %s second(s) before publishing image to face" %
99 (args.delay,)
100 )
101 rospy.sleep(args.delay)
102
103 send_image(args.file)
104 return 0
105
106 if __name__ == '__main__':
107 sys.exit(main())
The programs delays for the time specified by the user before publishing the image to Baxter's face. Then the send_image()
publishes the image as explained above.