Robotics StackExchange | Archived questions

could not convert image from '16SC1' to 'rgb8' ([16SC1] is not a color format. but [rgb8] is. The conversion does not make sense)

Hi, i need a small help with some matter that i cant wrap my head arround. it is not considering these repository but i may find some help here and that would appreciated. Im trying to publish a disparity map of a stereo camera, i wrote this node here and i keep getting this error when after starting the node : could not convert image from '16SC1' to 'rgb8' ([16SC1] is not a color format. but [rgb8] is. The conversion does not make sense) this is my node :

import rospy
import cv2 as cv
import numpy as np
from cv_bridge import CvBridge, CvBridgeError
from sensor_msgs.msg import Image
import message_filters

def read_cameras():
    imageL = message_filters.Subscriber("/camera_left/image_raw", Image)
    imageR = message_filters.Subscriber("/camera_Right/image_raw", Image)


    # Synchronize images
    ts = message_filters.ApproximateTimeSynchronizer([imageL, imageR], queue_size=10, slop=0.5)
    ts.registerCallback(image_callback)
    rospy.spin()

def image_callback(imageL, imageR):
    br = CvBridge()
    rospy.loginfo("receiving Image")

    imageLeft = br.imgmsg_to_cv2(imageL, "rgb8")
    imageRight = br.imgmsg_to_cv2(imageR, "rgb8")

    imageL_new=cv.cvtColor(imageLeft, cv.COLOR_BGR2GRAY)

    imageR_new=cv.cvtColor(imageRight, cv.COLOR_BGR2GRAY)



    stereo = cv.StereoBM_create(numDisparities=16, blockSize=15)
    disparity = stereo.compute(imageR_new,imageL_new)






    rospy.loginfo("showing depth image")
    # Process images...

    pub = rospy.Publisher('/left_camera', Image, queue_size=1)
    cv.imshow('disparity', disparity)
    msg = br.cv2_to_imgmsg(disparity, encoding='16SC1')
    pub2 = rospy.Publisher('/Right_camera', Image, queue_size=1)
    msg2 = br.cv2_to_imgmsg(disparity, encoding='16SC1')


    pub.publish(msg)
    pub2.publish(msg2)




if __name__ == '__main__':
    rospy.init_node('my_node')
    try:
        read_cameras()

    except rospy.ROSInterruptException:
        pass

is this an encoding Problem ? can someone tell me what im doing wrong exactly? i tried multiple approaches as to change the encodings but that didnt change. Anyhelp would be appreciated. thanks

Asked by aristow on 2022-11-16 08:38:58 UTC

Comments

Have you checked the data of imageLeft and imageRight using opencv imshow function?

If you are not getting imageLeft and Right perfectly then I think you need to change rgb8 to bgr8.

imageLeft = br.imgmsg_to_cv2(imageL, "rgb8") # bgr8

Asked by Ranjit Kathiriya on 2022-11-18 08:54:44 UTC

Answers