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

Extracting kinect depth_registered image

asked 2013-04-09 05:09:12 -0500

updated 2016-10-24 08:34:41 -0500

ngrennan gravatar image

Hi everybody,

I am using Ubuntu 12.10 with ROS Groovy. My problem is that I would like to extract the depth_registered image, in the same way I do it with the rgb image (in order to be able to do some processing outside ROS).

Basically, I am using the tutorial Exporting image and video data. But for depth, it doesn't work, because image is either float, either uint (see here for details on format)... but not bgr8 like image_view would like...

Any idea of another package doing the same thing ? Or how I could have my images quickly, without doing all the computation by hand (or writing a node doing the transformation format) ?

Thanks in advance,

Bests regards,

Stéphane

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
2

answered 2013-04-11 04:50:38 -0500

updated 2013-07-16 07:23:43 -0500

Hi everybody,

so the solution is to take the extract_images file from the package image_view, and to modify it :

just modify the

bgr8

and

mono8

to

sensor_msgs::image_encodings::TYPE_32FC1

Don't forget to add at the top :

#include <sensor_msgs/image_encodings.h>

Last but not least add in your manifest

<depend package="cv_bridge"/>

The results will be, as in the original file, jpg files. However, don't be frightened if they look black, because values are given in meter (for depth_registered/image).

Here is the whole code :

// modified version for depth extraction

/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <opencv2/highgui/highgui.hpp>

#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>

#include <boost/thread.hpp>
#include <boost/format.hpp>

class ExtractImages
{
private:
  image_transport::Subscriber sub_;

  sensor_msgs::ImageConstPtr last_msg_;
  boost::mutex image_mutex_;

  std::string window_name_;
  boost::format filename_format_;
  int count_;
  double _time;
  double sec_per_frame_;

#if defined(_VIDEO)
  CvVideoWriter* video_writer;
#endif //_VIDEO

public:
  ExtractImages(const ros::NodeHandle& nh, const std::string& transport)
    : filename_format_(""), count_(0), _time(ros::Time::now().toSec())
  {
    std::string topic = nh.resolveName("image");
    ros::NodeHandle local_nh("~");

    std::string format_string;
    local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
    filename_format_.parse(format_string);

    local_nh.param("sec_per_frame", sec_per_frame_, 0.1);

    image_transport::ImageTransport it(nh);
    sub_ = it.subscribe(topic, 1, &ExtractImages::image_cb, this, transport);

#if defined(_VIDEO)
    video_writer = 0;
#endif

    ROS_INFO("Initialized sec per frame to %f", sec_per_frame_);
  }

  ~ExtractImages()
  {
  }

  void image_cb(const sensor_msgs::ImageConstPtr& msg)
  {
    boost::lock_guard<boost::mutex> guard(image_mutex_);

    // Hang on to message pointer for sake of mouse_cb
    last_msg_ = msg;

    // May want to view raw bayer data
    // NB: This is hacky, but should be OK since we have ...
(more)
edit flag offensive delete link more

Comments

Hi, Thanks for the answer. I tried your code but i still get black jpg images. What i would like to have is images similar to /depth_registered/image so I can extract depth information to generate point clouds. Can you tell me how to achieve that? Thanks,

Faizan A. gravatar image Faizan A.  ( 2013-07-16 07:11:58 -0500 )edit
1

Black jpeg images is normal, as the information is coded as a distance, so it won't go until value 255 :-) if you try to watch the images (for example in matlab with the function imagesc) you will see what I mean. I edited my answer to have also a synchronized extraction of rgb and depth.

Stephane.M gravatar image Stephane.M  ( 2013-07-16 07:17:04 -0500 )edit
1

What I mean is that you have to "rescale" the pixel intensity values of the images in order to have an image "as you see in ROS".

Stephane.M gravatar image Stephane.M  ( 2013-07-16 07:32:39 -0500 )edit

That did the trick for me. Thanks a lot Stephane :)

Faizan A. gravatar image Faizan A.  ( 2013-07-16 22:37:04 -0500 )edit

Question Tools

Stats

Asked: 2013-04-09 05:09:12 -0500

Seen: 2,263 times

Last updated: Jul 16 '13