ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
![]() | 1 | initial version |
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_1UC1, 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.
![]() | 2 | No.2 Revision |
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_1UC1, 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.