Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

cv_bridge::toCvCopy() segfaults on some inputs #20

Closed
astaa-nrec opened this issue Aug 26, 2013 · 8 comments
Closed

cv_bridge::toCvCopy() segfaults on some inputs #20

astaa-nrec opened this issue Aug 26, 2013 · 8 comments

Comments

@astaa-nrec
Copy link

The following program crashes with a segmentation fault.

#include <ros/ros.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/Image.h>

#include <iostream>

int main() {

    sensor_msgs::Image image;
    cv_bridge::CvImagePtr cv_ptr;

    image.encoding = "bgr8";
    image.height = 200;
    image.width = 200;

    try {
        cv_ptr = cv_bridge::toCvCopy(image, "mono8");
    } catch (cv_bridge::Exception& e) {
        ROS_ERROR("cv_bridge exception: %s", e.what());
    }
}

Note that line 339 of cv_bridge.cpp constructs a matrix like this:

  const cv::Mat tmp((int)source.height, (int)source.width, source_type,
                    const_cast<uint8_t*>(&source.data[0]), (size_t)source.step);

This call is unsafe if source.data is empty, or if source.height, source.width, and source.step do not accurately describe source.data.

Therefore, either:

  1. toCvCopy() should validate that source is well-formed before calling this constructor, or
  2. the cv_bridge documentation / tutorials should indicate that it is unsafe to call toCvCopy() on an inconsistent sensor_msgs/Image message.

Note, furthermore, that toCvShare() appears to suffer from a similar problem.

@vrabaud
Copy link
Contributor

vrabaud commented Sep 4, 2013

ok. With 1) , you can only check that data is not 0. Otherwise, you could have a valid pointer for an mount of data, then change width for example, and get a valid pointer with an invalid description. Therefore 1) can never be perfect and I'd rather not create a false feeling of safety.
2) is the way to go and it seems obvious to me but I'll write something in the doc if you want, sure.

@vrabaud
Copy link
Contributor

vrabaud commented Sep 4, 2013

ok, done, thx. I completed the sentence:
You should always wrap your calls to toCvCopy() / toCvShared() to catch conversion errors.
by
You should always wrap your calls to toCvCopy() / toCvShared() to catch conversion errors as those functions will not check for the validity of your data.

@vrabaud vrabaud closed this as completed Sep 4, 2013
@astaa-nrec
Copy link
Author

Are you sure that 1) is not possible? source.data is a std::vector, not a raw pointer. In particular, it knows its own length. I'm wondering what would be wrong with checking, for example, that source.data.size() > 0 and that source.data.size() == source.height * source.step? (I'm not certain that these are precisely the correct checks to make, but it seems that something like them should be.)

As for 2), the new documentation is still misleading, as it still seems to indicate that an exception is the worst possible outcome. On the contrary, these functions can cause your whole program to crash irrecoverably! The following would be better:

You should always wrap your calls to toCvCopy() / toCvShared() to catch conversion errors. Moreover, you should be careful to only call these functions with well-formed input, as they may crash your program or corrupt memory if given ill-formed inputs, e.g. inputs whose dimensions do not match the length of their data.

@vrabaud
Copy link
Contributor

vrabaud commented Sep 9, 2013

Right on both, will fix asap.

@vrabaud vrabaud reopened this Sep 9, 2013
@vrabaud vrabaud closed this as completed in bb3b694 Oct 6, 2013
@astaa-nrec
Copy link
Author

I just took another look at your fix: bb3b694

I'm not so sure that it is correct to throw an error on source.height > source.step. The body of the toImageMsg() function seems to imply that source.step is some multiple of source.width and bears no necessary relation to source.height. Consider, in particular, the lines:

  ros_image.height = image.rows;
  ros_image.width = image.cols;
  ...
  ros_image.step = image.cols * image.elemSize();

Therefore, the requirement that source.height <= source.step seems to rule out some images that are valid, e.g. images that are taller than they are wide.

Perhaps you meant instead to require that source.width <= source.step? If we can assume that elemSize() is at least 1, then I think that would make sense.

@vrabaud
Copy link
Contributor

vrabaud commented Oct 23, 2013

yeah, obviously, why the hell did I do that ! Anyway, fixed and improved in ee10a9d
Please confirm and I'll release that.

@astaa-nrec
Copy link
Author

Looks good to me.

@vrabaud
Copy link
Contributor

vrabaud commented Oct 23, 2013

ok, re-releasing then !

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants