Skip to content

Instantly share code, notes, and snippets.

@awesomebytes
Created July 21, 2016 09:57
Show Gist options
  • Save awesomebytes/30bf7eae3a90754f82502accd02cbb12 to your computer and use it in GitHub Desktop.
Save awesomebytes/30bf7eae3a90754f82502accd02cbb12 to your computer and use it in GitHub Desktop.
Fix [16UC1] is not a color format. but [mono8] is. The conversion does not make sense

How to fix xtion's image format conversion

We may get:

cv_bridge exception: [16UC1] is not a color format. but [mono8] is. The conversion does not make sense

In C++ a workaround:

const sensor_msgs::ImageConstPtr & msg
					if (msg->encoding == "16UC1"){
						sensor_msgs::Image img;
						img.header = msg->header;
						img.height = msg->height;
						img.width = msg->width;
						img.is_bigendian = msg->is_bigendian;
						img.step = msg->step;
						img.data = msg->data;
						img.encoding = "mono16";

						cv_ptr = cv_bridge::toCvCopy(img, enc::MONO8);
					}

In Python

Being data the Image message from a subscription callback...

bridge = CvBridge()
data.encoding = "mono16"
cvImage = bridge.imgmsg_to_cv2(data, "mono8")
@ShinChoon
Copy link

In Cpp I have to use

sensor_msgs::image_encodings::MONO8

not enc:: ?!

But my image is just black ... :(

Also what I do not understand why do we need MONO8 and not MONO16?

I guesss you are doing something with ORB SLAM and ROS?
The modification below is how I avoid this error.

In example code: ros_stereo_inertial.cc, find function:
cv::Mat ImageGrabber::GetImage(const sensor_msgs::ImageConstPtr &img_msg)
Replace

  try
  {
    cv_ptr = cv_bridge::toCvShare(img_msg, sensor_msgs::image_encodings::MONO8);
  }
  catch (cv_bridge::Exception& e)
  {
    ROS_ERROR("cv_bridge exception: %s", e.what());
  }
  

With

  try
  {
    sensor_msgs::Image img;
    img.header = img_msg->header;
    img.height = img_msg->height;
    img.width = img_msg->width;
    img.is_bigendian = img_msg->is_bigendian;
    img.step = img_msg->step;
    img.data = img_msg->data;
    img.encoding = img_msg->encoding;
  if (img_msg->encoding == "8UC1"){
            img.encoding = "mono8";
            cv_ptr = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::MONO8);

          }
    else if(img_msg->encoding == "16UC1"){
            img.encoding = "mono16";
            cv_ptr = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::MONO8);

          }
    else
      cv_ptr = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::MONO8);
  }

  catch (cv_bridge::Exception& e)
  {
    ROS_ERROR("cv_bridge exception: %s", e.what());
  }

@konan6915
Copy link

The problem is that the information will be lost in this way. For me, I have thought of this method myself, but the loss of information makes me think this is not a good method.So I'm looking for other ways

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment