How to get correct depth value using kinect? I get all 0

asked 2017-08-14 22:42:19 -0500

mzWang gravatar image

Hey,

I'm new to opencv and all computer vision stuff. I'm trying to get the depth of one specific pixel point from the kinect image. I get the code how to get un-encoded depth from the topic /kinect2/hd/image_depth_rect

  void depthcb(const sensor_msgs::ImageConstPtr& msg)
{
        cv_bridge::CvImageConstPtr depth_img_cv;
        cv::Mat depth_mat;
        // Get the ROS image to openCV
        depth_img_cv = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::TYPE_16UC1);
        // Convert the uints to floats
        depth_img_cv->image.convertTo(depth_mat, CV_32F, 0.001);

        float depth = depth_img_cv->image.at<float>(10,10);

        ROS_INFO("Depth: %f", depth);

}

int main(int argc, char* argv[])
{
    ros::init(argc, argv, "depth");
    ros::NodeHandle nh;
    ros::Subscriber sub = nh.subscribe("/kinect2/hd/image_depth_rect", 1000, depthcb);
    ros::spin();
    return 0;
}

But I get all 0 output for the depth, and I tried quite few different pixels. If I understand this right, the pixel coordinate should be within the range (1080,1920) for kinect v2 ?

I'm pretty sure the kinect is working fine since when I echo kinect2/hd/image_depth_rect I get nonzeros and the output image looks right to me. Any idea what I did wrong?

Many thanks!

image description

edit retag flag offensive close merge delete

Comments

What package(s) are you using?

jayess gravatar image jayess  ( 2017-08-14 23:06:13 -0500 )edit

Hey jayess, I'm using iai-kinect2 to get kinect2 output for ros

mzWang gravatar image mzWang  ( 2017-08-14 23:08:56 -0500 )edit

How are you running iai-kinect2? The FAQ:

Point clouds are only published when the launch file is used. Make sure to start kinect2_bridge with roslaunch kinect2_bridge kinect2_bridge.launch.

jayess gravatar image jayess  ( 2017-08-15 18:21:39 -0500 )edit

Did you solve the issue ?

karl gravatar image karl  ( 2020-04-13 05:46:41 -0500 )edit