This example demonstrates how to display a given image file or multiple files on the robot´s face.
Contents
Introduction
The camera display example demonstrates how to pass image file(s) to robot head for display. The example read and convert image file(s) using cv_bridge
, sending the image info to the robot head screen as a standard ROS Image Message. If you would like to follow along with the actual source code for the example on GitHub, it can be found through this link for head display image example.
Usage
Run the example as following command:
$ rosrun intera_examples head_display_image.py -f <the path to image file to send>
Arguments
Important Arguments:
-f or --file : File path for display.
-l or --loop : Display images in loop.
-r or --rate : The frequency for multiple and looped images.
usage: head_display_image.py [-h] [-f FILE [FILE ...]] [-l] [-r RATE]
RSDK Head Display Example:
Displays a given image file or multiple files on the robot.s face.
Pass the relative or absolute file path to an image file on your
computer, and the example will read and convert the image using
cv_bridge, sending it to the screen as a standard ROS Image Message.
optional arguments:
-h, --help show this help message and exit
-l, --loop Display images in loop, add argument will display
images in loop
-r RATE, --rate RATE Image display frequency for multiple and looped
images.
required arguments:
-f FILE [FILE ...], --file FILE [FILE ...]
Path to image file to send. Multiple files are
separated by a space, eg.: a.png b.png
Notes:
Max screen resolution is 1024x600.
Images are always aligned to the top-left corner.
Image formats are those supported by OpenCv - LoadImage().
Code Walkthrough
Now, let's break down the code.
import intera_interface
import argparse
import rospy
This imports the intera interface for accessing the HeadDisplay class.
def main():
"""RSDK Head Display Example:
Displays a given image file or multiple files on the robot's face.
Pass the relative or absolute file path to an image file on your
computer, and the example will read and convert the image using
cv_bridge, sending it to the screen as a standard ROS Image Message.
"""
epilog = """
Notes:
Max screen resolution is 1024x600.
Images are always aligned to the top-left corner.
Image formats are those supported by OpenCv - LoadImage().
"""
arg_fmt = argparse.RawDescriptionHelpFormatter
parser = argparse.ArgumentParser(formatter_class=arg_fmt,
description=main.__doc__,
epilog=epilog)
required = parser.add_argument_group('required arguments')
required.add_argument(
'-f', '--file', nargs='+',
help='Path to image file to send. Multiple files are separated by a space, eg.: a.png b.png'
)
parser.add_argument(
'-l', '--loop', action="store_true",
help='Display images in loop, add argument will display images in loop'
)
parser.add_argument(
'-r', '--rate', type=float, default=1.0,
help='Image display frequency for multiple and looped images'
)
args = parser.parse_args()
Arguments for head image display, the image file(s) is a required argument, loop and rate are optional.
rospy.init_node("head_display_example", anonymous=True)
head_display = intera_interface.HeadDisplay()
head_display.display_image(args.file, args.loop, args.rate)
if __name__ == '__main__':
main()
The node is initialized and an instance of the HeadDisplay class is created. Call display_image function by passing in arguments. Press Ctrl-C to quit the example.
Was this article helpful?
That’s Great!
Thank you for your feedback
Sorry! We couldn't be helpful
Thank you for your feedback
Feedback sent
We appreciate your effort and will try to fix the article