We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
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
The following minimal example converts a 16bit integer image to a compressed message and back using the PNG format:
#include <cv_bridge/cv_bridge.h> #include <opencv2/opencv.hpp> #include <iostream> int main(int argc, char * argv[]) { // create 16bit integer image const std::string fmt = sensor_msgs::image_encodings::MONO16; cv_bridge::CvImage im0; im0.image = cv::Mat(100, 100, cv_bridge::getCvType(fmt)); im0.image = 2500; im0.encoding = fmt; std::cout << "orig type: " << im0.image.type() << std::endl; double max_org; cv::minMaxLoc(im0.image, nullptr, &max_org); std::cout << "orig max: " << max_org << std::endl; // convert to message and back sensor_msgs::CompressedImage::ConstPtr msg = im0.toCompressedImageMsg(cv_bridge::PNG); cv_bridge::CvImage im1 = *cv_bridge::toCvCopy(msg, fmt).get(); std::cout << "converted type: " << im1.image.type() << std::endl; double max_conv; cv::minMaxLoc(im1.image, nullptr, &max_conv); std::cout << "converted max: " << max_conv << std::endl; return 0; }
I would expect that the original data is restored. However, I get different results when converting it back.
orig type: 2 orig max: 2500 converted type: 2 converted max: 2570
If this would be a 16bit depth image, you would get an error of 7cm on 2.5m.
The text was updated successfully, but these errors were encountered:
Successfully merging a pull request may close this issue.
The following minimal example converts a 16bit integer image to a compressed message and back using the PNG format:
I would expect that the original data is restored. However, I get different results when converting it back.
If this would be a 16bit depth image, you would get an error of 7cm on 2.5m.
The text was updated successfully, but these errors were encountered: