image_publisher.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # simple script to publish a image from a file.
00003 import rospy
00004 import rospkg
00005 import time
00006 import cv2
00007 import sensor_msgs.msg
00008 
00009 def callback(self):
00010     """ Convert a image to a ROS compatible message
00011         (sensor_msgs.Image).
00012     """
00013     global publisher, imagePath
00014 
00015     img = cv2.imread(imagePath, cv2.IMREAD_UNCHANGED)
00016 
00017 #    print img.shape
00018 #    print img.size
00019 #    print img.dtype.itemsize
00020 
00021     rosimage = sensor_msgs.msg.Image()
00022     if img.dtype.itemsize == 2:
00023        if len(img.shape) == 3:
00024            if img.shape[2] == 3:
00025                rosimage.encoding = 'bgr16'
00026            if img.shape[2] == 4:
00027                    rosimage.encoding = 'bgra16'
00028        else:
00029            rosimage.encoding = 'mono16'
00030     if img.dtype.itemsize == 1:
00031        if len(img.shape) == 3:
00032            if img.shape[2] == 3:
00033                rosimage.encoding = 'bgr8'
00034            if img.shape[2] == 4:
00035                    rosimage.encoding = 'bgra8'
00036        else:
00037            rosimage.encoding = 'mono8'
00038 #    print "Encoding: ", rosimage.encoding
00039 
00040     rosimage.width = img.shape[1]
00041     rosimage.height = img.shape[0]
00042     rosimage.step = img.strides[0]
00043     rosimage.data = img.tostring()
00044     rosimage.header.stamp = rospy.Time.now()
00045     rosimage.header.frame_id = 'map'
00046 
00047     publisher.publish(rosimage)
00048 
00049 
00050 #Main function initializes node and subscribers and starts the ROS loop
00051 def main_program():
00052     global publisher, imagePath
00053     rospack = rospkg.RosPack()
00054     rospy.init_node('image_publisher')
00055     imagePath = rospy.get_param('~image_path')
00056     topicName = rospy.get_param('~topic')
00057     publisher = rospy.Publisher(topicName, sensor_msgs.msg.Image, queue_size=10)
00058     rospy.Timer(rospy.Duration(2), callback)
00059     rospy.spin()
00060 
00061 if __name__ == '__main__':
00062     try:
00063         main_program()
00064     except rospy.ROSInterruptException: pass


grid_map_demos
Author(s): Péter Fankhauser
autogenerated on Tue Jul 9 2019 05:06:58