The easiest way of achieving what you want is to use a 16 bit integer image format. These are commonly used for depth images because standard image codecs support this format, and there is enough range to usefully describe the depth information.
You will probably need to check that this solution will work for the type of depth sensor you're using.
If a measurement of mm is used then an unsigned 16 bit integer can represent a range of depths from zero to 65.5 meters. All depths sensors I've ever seen have a maximum depth lower than this as well as a minimum depth somewhere between 30cm and a meter. This is why a depth of zero is used as a special value meaning no depth data available. You could use the same technique and use a depth of 1mm (again outside the range of values from the sensor) to encode a NAN value.
The code do this will look something like this. You'll need to convert the float depth value (which by convention should be in meters, but you'll need to check this) into mm. This code assumes that cv_ptr_depth_
is a pointer to an open CV Mat using single channel 32 bit float encoding in meters.
cv::Mat myMat = Mat(376, 672, CV_16UC1, cv::Scalar(1));
for(int i = 0; i < nRows; ++i){
for (int j = 0; j < nCols; ++j){
if(img.at<uchar>(i,j) != 0)
myMat.at<unsigned short>(i,j) = cv_ptr_depth_->image.at<float>(i,j) * 100.0;
}
}
cv_bridge::CvImage depth_filtered_;
depth_filtered_.header.frame_id = depth_msg_->header.frame_id;
depth_filtered_.header.stamp = depth_msg_->header.stamp;
depth_filtered_.encoding = "mono16";
depth_filtered_.image = myMat;
Depth_Filter::image_pub_.publish(depth_filtered_.toImageMsg());
You'll have to do the reverse of this if you need to process it as a float image with NANs on the other side, but this way it is compatible with ROS image messages and can be viewed in RVIZ and other tools.
Hope this helps.
The NANs are being lost when they're converted to integers during image transport. You'd need a floating point image format to be able to transmit this information within an image. I don't know if this is currently possible with the image encoders supported.
Could you use an out of range value such as zero instead of NAN? That would make your scheme work with standard image formats.
Hi, thank you for your replay. I do indeed need the ros topic image with nan values.This is the piece of code of the node. Do you have a clue how to solve this issue :) thank you.
I'm confused as to why you need to transmit NANs. The code above is simply converting zeros to NANs, and using a 32bit float representation to store values between 1-255.
Very few image encodings are designed to store floating point values. TIFF is the only one I can think of, and I don't think it's supported by the ROS image messaging system.
Okay, thanks for the update, the code make more sense.
Fundamentally your problem is trying to transfer float type images via ROS. If you're transmitting depth images, then int16 is the common choice. It's got enough range you can encode with mm depth precision, and there's generally enough redundancy to define several special values so you can encode you're NAN elements.
Hi, thank you for the replay. You mean change the line:
myMat.at<float>(i,j) = cv_ptr_depth_->image.at<float>(i,j);
to<uint16_t>(i,j) = cv_ptr_depth_->image.at<uint16_t>(i,j);
By the way looking at the source code of cv_bridge.cpp
if (source->encoding == enc::TYPE_32FC1) {
Or how can I encode the nan values?? :) thank you