ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

@PeteBlackerThe3rd is right about the units. The package depth_image_proc has functions to convert between the two versions. If the rest of your code is expecting the uint16_t version, you can do something like the following:

if ("16UC1" == depth_msg->encoding)
{
    try
    {
        cv_depth_ptr = cv_bridge::toCvCopy(depth_msg, sensor_msgs::image_encodings::TYPE_16UC1);
    }
    catch (cv_bridge::Exception& e)
    {
        ROS_ERROR("cv_bridge exception: %s", e.what());
        return false;
    }
}
else if ("32FC1" == depth_msg->encoding)
{
    try
    {
        cv_depth_ptr = cv_bridge::toCvCopy(depth_msg, sensor_msgs::image_encodings::TYPE_32FC1);
    }
    catch (cv_bridge::Exception& e)
    {
        ROS_ERROR("cv_bridge exception: %s", e.what());
        return false;
    }

    cv::Mat convertedDepthImg(cv_depth_ptr->image.size(), CV_16UC1);

    const int V = cv_depth_ptr->image.size().height;
    const int U = cv_depth_ptr->image.size().width;

    #pragma omp parallel for
    for (int v = 0; v < V; ++v)
    {
        for (int u = 0; u < U; ++u)
        {
            convertedDepthImg.at<uint16_t>(v, u)
                = depth_image_proc::DepthTraits<uint16_t>::fromMeters(cv_depth_ptr->image.at<float>(v, u));
        }
    }

    cv_depth_ptr->encoding = "16UC1";
    cv_depth_ptr->image = convertedDepthImg;
}

with datatypes:

sensor_msgs::ImageConstPtr depth_msg;
cv_bridge::CvImagePtr cv_depth_ptr;

Although, it might make more sense to convert the mm version to float, since you probably actually care about the depth in meters anyway.