how to get an open cv image from an image subscriber

asked 2019-08-07 14:34:52 -0500

brian77754 gravatar image

updated 2019-08-07 14:53:13 -0500

I have a program that detects laser points that I know works when I read an image from video 0 but I do not know how to make the program work from a ros subscriber image. I need to know how to convert a ros image subscriber into a usable opencv image named "image" I have researched how to do this and I have come across several solutions that all use the function bridge.imgmsg_to_cv2 but I can not get this to work I am sure it is a simple fix I just don't know what I am doing. This should be relatively simple though. here is my code:

# import the necessary packages
from __future__ import print_function
from imutils import contours
from skimage import measure
import numpy as np
import argparse
import imutils
import cv2
import message_filters
from sensor_msgs.msg import Image, CameraInfo
from std_msgs.msg import Int32, Float32MultiArray
import rospy
from cv_bridge import CvBridge, CvBridgeError


import roslib
roslib.load_manifest('my_package')
import sys
import rospy
import cv2
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError

'''
def getPoint(cameraTip,dotXY,normalPoint):
    slope= (cameraTip[2]-dotXY[2])/(cameraTip[1]-dotXY[1])
    b=cameraTip[2]-(slope*cameraTip[1])
    z=slope*normalPoint[1]+b
    return [normalPoint[0],normalPoint[1],z]
'''
class image_converter:
    def __init__(self):
        self.image_pub = rospy.Publisher("image_topic_2",Image)
        self.bridge = CvBridge()
        self.image_sub = rospy.Subscriber("CM_040GE/image_raw",Image,self.callback)

    def callback(self,data):
        try:
            cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
        except CvBridgeError as e:
            print(e)

        (rows,cols,channels) = cv_image.shape
        if cols > 60 and rows > 60 :
            cv2.circle(cv_image, (50,50), 10, 255)

        cv2.imshow("Image window", cv_image)
        cv2.waitKey(3)

        try:
            self.image_pub.publish(self.bridge.cv2_to_imgmsg(cv_image, "bgr8"))
        except CvBridgeError as e:
            print(e)

    def main(args):
        ic = image_converter()
        rospy.init_node('image_converter', anonymous=True)
        try:
            rospy.spin()
        except KeyboardInterrupt:
            print("Shutting down")
            cv2.destroyAllWindows()
        if __name__ == '__main__':
            main(sys.argv)
image = bridge.imgmsg_to_cv2(image_message, desired_encoding="passthrough")
while(1):



    gray = cv2.cvtColor(image, cv2.COLOR_BGR2GRAY)
    blurred = cv2.GaussianBlur(gray, (11, 11), 0)
        #threshold the image to reveal light regions in the
        # blurred image
    thresh = cv2.threshold(blurred, 30, 255, cv2.THRESH_BINARY)[1]
        # perform a series of erosions and dilations to remove
        # any small blobs of noise from the thresholded image
    thresh = cv2.erode(thresh, None, iterations=2)
    thresh = cv2.dilate(thresh, None, iterations=4)
        # perform a connected component analysis on the thresholded
        # image, then initialize a mask to store only the "large"
        # components
    labels = measure.label(thresh, neighbors=8, background=0)
    mask = np.zeros(thresh.shape, dtype="uint8")

        # loop over the unique components
    for label in np.unique(labels):
            # if this is the background label, ignore it
        if label == 0:
            continue

            # otherwise, construct the label mask and count the
                # number of pixels 
        labelMask = np.zeros(thresh.shape, dtype="uint8")
        labelMask[labels == label] = 255
        numPixels = cv2.countNonZero(labelMask)

                # if the number of pixels in the component is sufficiently
                # large, then add it to our mask of "large blobs"
        if ...
(more)
edit retag flag offensive close merge delete