Skip to content

Commit

Permalink
Fix final confusion between format and encoding.
Browse files Browse the repository at this point in the history
Format is file format like jpg, bmp and more,
encoding is color encoding like bgr8, rgb8 and more.
  • Loading branch information
talregev committed May 10, 2019
1 parent 33f59e5 commit d9ce593
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 23 deletions.
2 changes: 1 addition & 1 deletion cv_bridge/include/cv_bridge/cv_bridge.h
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@ struct CvtColorForDisplayOptions {
* encoding image is passed.
* - if the output encoding is not empty, it must have sensor_msgs::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
* - if the input encoding is an OpenCV encoding (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.
Expand Down
4 changes: 2 additions & 2 deletions cv_bridge/python/cv_bridge/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ def compressed_imgmsg_to_cv2(self, cmprs_img_msg, desired_encoding = "passthroug
:rtype: :cpp:type:`cv::Mat`
:raises CvBridgeError: when conversion is not possible.
If desired_encoding is ``"passthrough"``, then the returned image has the same format as img_msg.
If desired_encoding is ``"passthrough"``, then the returned image has the same encoding as img_msg.
Otherwise desired_encoding must be one of the standard image encodings
This function returns an OpenCV :cpp:type:`cv::Mat` message on success, or raises :exc:`cv_bridge.CvBridgeError` on failure.
Expand Down Expand Up @@ -151,7 +151,7 @@ def imgmsg_to_cv2(self, img_msg, desired_encoding = "passthrough"):
:rtype: :cpp:type:`cv::Mat`
:raises CvBridgeError: when conversion is not possible.
If desired_encoding is ``"passthrough"``, then the returned image has the same format as img_msg.
If desired_encoding is ``"passthrough"``, then the returned image has the same encoding as img_msg.
Otherwise desired_encoding must be one of the standard image encodings
This function returns an OpenCV :cpp:type:`cv::Mat` message on success, or raises :exc:`cv_bridge.CvBridgeError` on failure.
Expand Down
40 changes: 20 additions & 20 deletions cv_bridge/src/cv_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,16 +134,16 @@ Encoding getEncoding(const std::string& encoding)
return INVALID;
}

static const int SAME_FORMAT = -1;
static const int SAME_ENCODING = -1;

/** Return a lit of OpenCV conversion codes to get from one Format to the other
* The key is a pair: <FromFormat, ToFormat> and the value a succession of OpenCV code conversion
/** Return a lit of OpenCV conversion codes to get from one encoding to the other
* The key is a pair: <FromEncoding, ToEncoding> and the value a succession of OpenCV code conversion
* It's not efficient code but it is only called once and the structure is small enough
*/
std::map<std::pair<Encoding, Encoding>, std::vector<int> > getConversionCodes() {
std::map<std::pair<Encoding, Encoding>, std::vector<int> > res;
for(int i=0; i<=5; ++i)
res[std::pair<Encoding, Encoding>(Encoding(i),Encoding(i))].push_back(SAME_FORMAT);
res[std::pair<Encoding, Encoding>(Encoding(i),Encoding(i))].push_back(SAME_ENCODING);

res[std::make_pair(GRAY, RGB)].push_back(cv::COLOR_GRAY2RGB);
res[std::make_pair(GRAY, BGR)].push_back(cv::COLOR_GRAY2BGR);
Expand Down Expand Up @@ -200,30 +200,30 @@ const std::vector<int> getConversionCode(std::string src_encoding, std::string d
{
Encoding src_encod = getEncoding(src_encoding);
Encoding dst_encod = getEncoding(dst_encoding);
bool is_src_color_format = enc::isColor(src_encoding) || enc::isMono(src_encoding) ||
bool is_src_color_encoding = enc::isColor(src_encoding) || enc::isMono(src_encoding) ||
enc::isBayer(src_encoding) || (src_encoding == enc::YUV422);
bool is_dst_color_format = enc::isColor(dst_encoding) || enc::isMono(dst_encoding) ||
bool is_dst_color_encoding = enc::isColor(dst_encoding) || enc::isMono(dst_encoding) ||
enc::isBayer(dst_encoding) || (dst_encoding == enc::YUV422);
bool is_num_channels_the_same = (enc::numChannels(src_encoding) == enc::numChannels(dst_encoding));

// If we have no color info in the source, we can only convert to the same format which
// If we have no color info in the source, we can only convert to the same encoding which
// was resolved in the previous condition. Otherwise, fail
if (!is_src_color_format) {
if (is_dst_color_format)
throw Exception("[" + src_encoding + "] is not a color format. but [" + dst_encoding +
if (!is_src_color_encoding) {
if (is_dst_color_encoding)
throw Exception("[" + src_encoding + "] is not a color encoding. but [" + dst_encoding +
"] is. The conversion does not make sense");
if (!is_num_channels_the_same)
throw Exception("[" + src_encoding + "] and [" + dst_encoding + "] do not have the same number of channel");
return std::vector<int>(1, SAME_FORMAT);
return std::vector<int>(1, SAME_ENCODING);
}

// If we are converting from a color type to a non color type, we can only do so if we stick
// to the number of channels
if (!is_dst_color_format) {
if (!is_dst_color_encoding) {
if (!is_num_channels_the_same)
throw Exception("[" + src_encoding + "] is a color format but [" + dst_encoding + "] " +
throw Exception("[" + src_encoding + "] is a color encoding but [" + dst_encoding + "] " +
"is not so they must have the same OpenCV type, CV_8UC3, CV16UC1 ....");
return std::vector<int>(1, SAME_FORMAT);
return std::vector<int>(1, SAME_ENCODING);
}

// If we are converting from a color type to another type, then everything is fine
Expand All @@ -238,7 +238,7 @@ const std::vector<int> getConversionCode(std::string src_encoding, std::string d
// And deal with depth differences if the colors are different
std::vector<int> res = val->second;
if ((enc::bitDepth(src_encoding) != enc::bitDepth(dst_encoding)) && (getEncoding(src_encoding) != getEncoding(dst_encoding)))
res.push_back(SAME_FORMAT);
res.push_back(SAME_ENCODING);

return res;
}
Expand Down Expand Up @@ -320,7 +320,7 @@ CvImagePtr toCvCopyImpl(const cv::Mat& source,
cv::Mat image2;
for(size_t i=0; i<conversion_codes.size(); ++i) {
int conversion_code = conversion_codes[i];
if (conversion_code == SAME_FORMAT)
if (conversion_code == SAME_ENCODING)
{
// Same number of channels, but different bit depth
int src_depth = enc::bitDepth(src_encoding);
Expand Down Expand Up @@ -550,7 +550,7 @@ CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr& source,
{
try
{
// Let's decide upon an output format
// Let's decide upon an output encoding
if (enc::numChannels(source->encoding) == 1)
{
if ((source->encoding == enc::TYPE_32SC1) ||
Expand Down Expand Up @@ -661,13 +661,13 @@ CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr& source,
return cvtColor(img_scaled, encoding);
}

// If no color conversion is possible, we must "guess" the input format
// If no color conversion is possible, we must "guess" the input encoding
CvImagePtr source_typed(new CvImage());
source_typed->image = source->image;
source_typed->header = source->header;
source_typed->encoding = source->encoding;

// If we get the OpenCV format, if we have 1,3 or 4 channels, we are most likely in mono, BGR or BGRA modes
// If we get the OpenCV encoding, if we have 1,3 or 4 channels, we are most likely in mono, BGR or BGRA modes
if (source->encoding == "CV_8UC1")
source_typed->encoding = enc::MONO8;
else if (source->encoding == "16UC1")
Expand All @@ -687,7 +687,7 @@ CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr& source,

try
{
// Now that the output is a proper color format, try to see if any conversion is possible
// Now that the output is a proper color encoding, try to see if any conversion is possible
return cvtColor(source_typed, encoding);
}
catch (cv_bridge::Exception& e)
Expand Down

0 comments on commit d9ce593

Please sign in to comment.