Skip to content

Commit

Permalink
fix bad image check and improve it too
Browse files Browse the repository at this point in the history
  • Loading branch information
vrabaud committed Oct 23, 2013
1 parent 6dbed62 commit ee10a9d
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 2 deletions.
7 changes: 5 additions & 2 deletions cv_bridge/src/cv_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -235,11 +235,14 @@ const std::vector<int> getConversionCode(std::string src_encoding, std::string d
cv::Mat matFromImage(const sensor_msgs::Image& source)
{
int source_type = getCvType(source.encoding);
int byte_depth = enc::bitDepth(source.encoding) / 8;
int num_channels = enc::numChannels(source.encoding);

if (source.height > source.step)
if (source.step != source.width * byte_depth * num_channels)

This comment has been minimized.

Copy link
@jensenb

jensenb Nov 22, 2013

Contributor

This is offending invariant check that prevents aligned image as discussed in #27. I think this has to be:

if (source.step < source.width * byte_depth * num_channels)

This comment has been minimized.

Copy link
@vrabaud

vrabaud Nov 22, 2013

Author Contributor

yop, I had done that on purpose but I had misread the specs so I was wrong :) Fixing ASAP.

This comment has been minimized.

Copy link
@jensenb

jensenb Nov 22, 2013

Contributor

Great! I got a bit of a shock when I ran some of my bags files and rqt_image_view crashed due to a cv_bridge::Exception, where it had previously worked not that long ago. At least the error localization was quite easy.

{
std::stringstream ss;
ss << "Image is wrongly formed: height > step or " << source.height << " > " << source.step;
ss << "Image is wrongly formed: step != width * byte_depth * num_channels or " << source.step << " != " <<
source.width << " * " << byte_depth << " * " << num_channels;
throw Exception(ss.str());
}

Expand Down
8 changes: 8 additions & 0 deletions cv_bridge/test/utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,14 @@ TEST(CvBridgeTest, initialization)
} catch (cv_bridge::Exception& e) {
EXPECT_EQ(1, 1);
}

// Check some normal images with different ratios
for(int height = 100; height <= 300; ++height) {
image.encoding = sensor_msgs::image_encodings::RGB8;
image.step = image.width*3;
image.data.resize(image.height*image.step);
cv_ptr = cv_bridge::toCvCopy(image, "mono8");
}
}

int main(int argc, char** argv)
Expand Down

0 comments on commit ee10a9d

Please sign in to comment.