Esempio n. 1
0
    def update(self):
        '''
        Updates Image.
        '''
        if self.hasproxy():
            img = Image()
            imageData = self.proxy.getImageData(self.imgFormat)
            img.height = imageData.description.height
            img.width = imageData.description.width
            img.format = imageData.description.format

            # Format jdpeg input
            if img.format == "jpeg":
                data = cv2.imdecode(imageData.pixelData)
                img.data = cv.cvtColor(data, cv.COLOR_BGR2RGB)
                img.format = "RGB8"

            # When NOT Jpeg format input
            else:
                img.data = np.frombuffer(imageData.pixelData, dtype=np.uint8)
                img.data.shape = img.height, img.width, 3

            img.timeStamp = imageData.timeStamp.seconds + imageData.timeStamp.useconds * 1e-9

            self.lock.acquire()
            self.image = img
            self.lock.release()
Esempio n. 2
0
    def __init__(self, jdrc, prefix):
        '''
        Camera Contructor.
        Exits When it receives a Exception diferent to Ice.ConnectionRefusedException

        @param jdrc: Comm Communicator
        @param prefix: Name of client in config file

        @type jdrc: Comm Communicator
        @type prefix: String
        '''

        self.lock = threading.Lock()
        self.image = Image()

        try:

            ic = jdrc.getIc()
            proxyStr = jdrc.getConfig().getProperty(prefix + ".Proxy")
            basecamera = ic.stringToProxy(proxyStr)
            self.proxy = jderobot.CameraPrx.checkedCast(basecamera)
            self.imgFormat = jdrc.getConfig().getPropertyWithDefault(
                prefix + ".Format", "RGB8")

            self.update()

            if not self.proxy:
                print('Interface ' + prefix + ' not configured')

        except Ice.ConnectionRefusedException:
            print(prefix + ': connection refused')

        except:
            traceback.print_exc()
            exit(-1)
Esempio n. 3
0
    def __init__(self, ic, prefix):
        '''
        Camera Contructor.
        Exits When it receives a Exception diferent to Ice.ConnectionRefusedException

        @param ic: Ice Communicator
        @param prefix: prefix name of client in config file

        @type ic: Ice Communicator
        @type prefix: String
        '''

        self.lock = threading.Lock()
        self.image = Image()

        try:
            basecamera = ic.propertyToProxy(prefix + ".Proxy")
            self.proxy = jderobot.CameraPrx.checkedCast(basecamera)
            prop = ic.getProperties()
            self.imgFormat = prop.getProperty(prefix + ".Format")
            if not self.imgFormat:
                self.imgFormat = "RGB8"

            self.update()

            if not self.proxy:
                print('Interface ' + prefix + ' not configured')

        except Ice.ConnectionRefusedException:
            print(prefix + ': connection refused')

        except:
            traceback.print_exc()
            exit(-1)
Esempio n. 4
0
def imageMsg2Image(img, bridge):
    '''
    Translates from ROS Image to JderobotTypes Image. 

    @param img: ROS Image to translate
    @param bridge: bridge to do translation

    @type img: sensor_msgs.msg.Image
    @type brige: CvBridge

    @return a JderobotTypes.Image translated from img

    '''
    image = Image()

    image.width = img.width
    image.height = img.height
    image.format = "RGB8"
    image.timeStamp = img.header.stamp.secs + (img.header.stamp.nsecs * 1e-9)
    cv_image = 0
    if (img.encoding[-2:] == "C1"):
        gray_img_buff = bridge.imgmsg_to_cv2(img, img.encoding)
        cv_image = depthToRGB8(gray_img_buff, img.encoding)
    else:
        cv_image = bridge.imgmsg_to_cv2(img, "rgb8")
    image.data = cv_image
    return image
Esempio n. 5
0
def imageMsg2Image(img, bridge):
    '''
    Translates from ROS Image to JderobotTypes Image. 

    @param img: ROS Image to translate
    @param bridge: bridge to do translation

    @type img: sensor_msgs.msg.Image
    @type brige: CvBridge

    @return a JderobotTypes.Image translated from img

    '''
    image = Image()

    image.width = img.width
    image.height = img.height
    image.format = "RGB8"
    image.timeStamp = img.header.stamp.secs + (img.header.stamp.nsecs *1e-9)
    cv_image=0
    if (img.encoding == "32FC1"):
        gray_img_buff = bridge.imgmsg_to_cv2(img, "32FC1")
        cv_image  = depthToRGB8(gray_img_buff)
    else:
        cv_image = bridge.imgmsg_to_cv2(img, "rgb8")
    image.data = cv_image
    return image
Esempio n. 6
0
    def getImage(self):
        '''
        Returns last Image. 

        @return last JdeRobotTypes Image saved

        '''
        img = Image()
        if self.hasproxy():
            self.lock.acquire()
            img = self.image
            self.lock.release()
        return img
Esempio n. 7
0
    def __init__(self, topic):
        '''
        ListenerCamera Constructor.

        @param topic: ROS topic to subscribe
        
        @type topic: String

        '''
        self.topic = topic
        self.data = Image()
        self.sub = None
        self.lock = threading.Lock()

        self.bridge = CvBridge()
        self.start()
Esempio n. 8
0
    def __init__(self, topic, ros2node):
        '''
        ListenerCamera Constructor.

        @param topic: ROS2 topic to subscribe
        
        @type topic: String

        '''
        self.topic = topic
        self.data = Image()
        self.sub = None
        self.lock = threading.Lock()

        self.__noderos2 = ros2node

        self.bridge = CvBridge()
        self.start()

        self.spin_thread = None  # variable to handle thread
Esempio n. 9
0
    def update(self):
        '''
        Updates Image.
        '''
        if self.hasproxy():
            img = Image()
            imageData = self.proxy.getImageData(self.imgFormat)
            img.height = imageData.description.height
            img.width = imageData.description.width
            img.format = imageData.description.format

            img.data = np.frombuffer(imageData.pixelData, dtype=np.uint8)
            img.data.shape = img.height, img.width, 3

            img.timeStamp = imageData.timeStamp.seconds + imageData.timeStamp.useconds * 1e-9

            self.lock.acquire()
            self.image = img
            self.lock.release()
Esempio n. 10
0
def imageComp2Image(img, bridge):
    '''
    Translates from ROS CompressedImage to JderobotTypes Image. 

    @param img: ROS CompressedImage to translate
    @param bridge: bridge to do translation

    @type img: sensor_msgs.msg.CompressedImage
    @type brige: CvBridge

    @return a JderobotTypes.Image translated from img
    '''

    image = Image()
    image.format = "RGB8"
    image.data = bridge.compressed_imgmsg_to_cv2(img, "rgb8")
    image.width = image.data.shape[0]
    image.height = image.data.shape[1]
    return image
Esempio n. 11
0
    def update(self):
        '''
        Updates Image.
        '''
        if self.hasproxy():
            img = Image()
            imageData = self.proxy.getImageData(self.imgFormat)
            img.height = imageData.description.height
            img.width = imageData.description.width
            img.format = imageData.description.format

            img.data = np.frombuffer(imageData.pixelData, dtype=np.uint8)
            img.data.shape = img.height, img.width, 3

            img.timeStamp = imageData.timeStamp.seconds + imageData.timeStamp.useconds * 1e-9


            self.lock.acquire()
            self.image = img
            self.lock.release()