Skip to content

Commit d9ce593

Browse files
committed
Fix final confusion between format and encoding.
Format is file format like jpg, bmp and more, encoding is color encoding like bgr8, rgb8 and more.
1 parent 33f59e5 commit d9ce593

File tree

3 files changed

+23
-23
lines changed

3 files changed

+23
-23
lines changed

cv_bridge/include/cv_bridge/cv_bridge.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -277,7 +277,7 @@ struct CvtColorForDisplayOptions {
277277
* encoding image is passed.
278278
* - if the output encoding is not empty, it must have sensor_msgs::image_encodings::isColor and
279279
* isMono return true. It must also be 8 bit in depth
280-
* - if the input encoding is an OpenCV format (e.g. 8UC1), and if we have 1,3 or 4 channels, it is
280+
* - if the input encoding is an OpenCV encoding (e.g. 8UC1), and if we have 1,3 or 4 channels, it is
281281
* respectively converted to mono, BGR or BGRA.
282282
* - if the input encoding is 32SC1, this estimate that image as label image and will convert it as
283283
* bgr image with different colors for each label.

cv_bridge/python/cv_bridge/core.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ def compressed_imgmsg_to_cv2(self, cmprs_img_msg, desired_encoding = "passthroug
111111
:rtype: :cpp:type:`cv::Mat`
112112
:raises CvBridgeError: when conversion is not possible.
113113
114-
If desired_encoding is ``"passthrough"``, then the returned image has the same format as img_msg.
114+
If desired_encoding is ``"passthrough"``, then the returned image has the same encoding as img_msg.
115115
Otherwise desired_encoding must be one of the standard image encodings
116116
117117
This function returns an OpenCV :cpp:type:`cv::Mat` message on success, or raises :exc:`cv_bridge.CvBridgeError` on failure.
@@ -151,7 +151,7 @@ def imgmsg_to_cv2(self, img_msg, desired_encoding = "passthrough"):
151151
:rtype: :cpp:type:`cv::Mat`
152152
:raises CvBridgeError: when conversion is not possible.
153153
154-
If desired_encoding is ``"passthrough"``, then the returned image has the same format as img_msg.
154+
If desired_encoding is ``"passthrough"``, then the returned image has the same encoding as img_msg.
155155
Otherwise desired_encoding must be one of the standard image encodings
156156
157157
This function returns an OpenCV :cpp:type:`cv::Mat` message on success, or raises :exc:`cv_bridge.CvBridgeError` on failure.

cv_bridge/src/cv_bridge.cpp

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -134,16 +134,16 @@ Encoding getEncoding(const std::string& encoding)
134134
return INVALID;
135135
}
136136

137-
static const int SAME_FORMAT = -1;
137+
static const int SAME_ENCODING = -1;
138138

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

148148
res[std::make_pair(GRAY, RGB)].push_back(cv::COLOR_GRAY2RGB);
149149
res[std::make_pair(GRAY, BGR)].push_back(cv::COLOR_GRAY2BGR);
@@ -200,30 +200,30 @@ const std::vector<int> getConversionCode(std::string src_encoding, std::string d
200200
{
201201
Encoding src_encod = getEncoding(src_encoding);
202202
Encoding dst_encod = getEncoding(dst_encoding);
203-
bool is_src_color_format = enc::isColor(src_encoding) || enc::isMono(src_encoding) ||
203+
bool is_src_color_encoding = enc::isColor(src_encoding) || enc::isMono(src_encoding) ||
204204
enc::isBayer(src_encoding) || (src_encoding == enc::YUV422);
205-
bool is_dst_color_format = enc::isColor(dst_encoding) || enc::isMono(dst_encoding) ||
205+
bool is_dst_color_encoding = enc::isColor(dst_encoding) || enc::isMono(dst_encoding) ||
206206
enc::isBayer(dst_encoding) || (dst_encoding == enc::YUV422);
207207
bool is_num_channels_the_same = (enc::numChannels(src_encoding) == enc::numChannels(dst_encoding));
208208

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

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

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

243243
return res;
244244
}
@@ -320,7 +320,7 @@ CvImagePtr toCvCopyImpl(const cv::Mat& source,
320320
cv::Mat image2;
321321
for(size_t i=0; i<conversion_codes.size(); ++i) {
322322
int conversion_code = conversion_codes[i];
323-
if (conversion_code == SAME_FORMAT)
323+
if (conversion_code == SAME_ENCODING)
324324
{
325325
// Same number of channels, but different bit depth
326326
int src_depth = enc::bitDepth(src_encoding);
@@ -550,7 +550,7 @@ CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr& source,
550550
{
551551
try
552552
{
553-
// Let's decide upon an output format
553+
// Let's decide upon an output encoding
554554
if (enc::numChannels(source->encoding) == 1)
555555
{
556556
if ((source->encoding == enc::TYPE_32SC1) ||
@@ -661,13 +661,13 @@ CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr& source,
661661
return cvtColor(img_scaled, encoding);
662662
}
663663

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

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

688688
try
689689
{
690-
// Now that the output is a proper color format, try to see if any conversion is possible
690+
// Now that the output is a proper color encoding, try to see if any conversion is possible
691691
return cvtColor(source_typed, encoding);
692692
}
693693
catch (cv_bridge::Exception& e)

0 commit comments

Comments
 (0)