ros-perception/vision_opencv

how to convert a 32FC1 image message to color formats?

thachdo opened this issue · 1 comments

Hello,

Can we convert a 32FC1 image message to color formats like rbg8 or bgr8?

I'm using the below function

cv_bridge::CvImagePtr cv_ptr;
try
{
  cv_ptr = cv_bridge::toCvCopy(gray_msg, sensor_msgs::image_encodings::BGR8);
}
catch (cv_bridge::Exception& e)
{
  ROS_ERROR("cv_bridge exception: %s", e.what());
  return;
}

and get below error:

[ERROR] [1668071878.177947865]: cv_bridge exception: [32FC1] is not a color format. but [bgr8] is. The conversion does not make sense

Is there a way to convert a gray image message to a color one directly?

ijnek commented

I'm going to assume you want to convert gray image to color image for display purposes. You could use cvtColorForDisplay, and must specify how you want to convert the grayscale to the color format with the CvtColorForDisplayOptions parameter.

/**
* \brief Converts an immutable sensor_msgs::msg::Image message to another CvImage for display purposes,
* using practical conversion rules if needed.
*
* Data will be shared between input and output if possible.
*
* Recall: sensor_msgs::msg::image_encodings::isColor and isMono tell whether an image contains R,G,B,A, mono
* (or any combination/subset) with 8 or 16 bit depth.
*
* The following rules apply:
* - if the output encoding is empty, the fact that the input image is mono or multiple-channel is
* preserved in the ouput image. The bit depth will be 8. it tries to convert to BGR no matter what
* encoding image is passed.
* - if the output encoding is not empty, it must have sensor_msgs::msg::image_encodings::isColor and
* isMono return true. It must also be 8 bit in depth
* - if the input encoding is an OpenCV format (e.g. 8UC1), and if we have 1,3 or 4 channels, it is
* respectively converted to mono, BGR or BGRA.
* - if the input encoding is 32SC1, this estimate that image as label image and will convert it as
* bgr image with different colors for each label.
*
* \param source A shared_ptr to a sensor_msgs::msg::Image message
* \param encoding Either an encoding string that returns true in sensor_msgs::msg::image_encodings::isColor
* isMono or the empty string as explained above.
* \param options (cv_bridge::CvtColorForDisplayOptions) Options to convert the source image with.
* - do_dynamic_scaling If true, the image is dynamically scaled between its minimum and maximum value
* before being converted to its final encoding.
* - min_image_value Independently from do_dynamic_scaling, if min_image_value and max_image_value are
* different, the image is scaled between these two values before being converted to its final encoding.
* - max_image_value Maximum image value
* - colormap Colormap which the source image converted with.
*/
CV_BRIDGE_EXPORT CvImageConstPtr cvtColorForDisplay(
const CvImageConstPtr & source,
const std::string & encoding = std::string(),
const CvtColorForDisplayOptions options = CvtColorForDisplayOptions());