0
$\begingroup$

Rosanswers logo

Hi,

I am new in ROS. I wanted to get both the depth and rgb image of an object at the same time and use it in the callback function. if I use it as mentioned below. It works for me.

void imageCallback(const sensor_msgs::ImageConstPtr& kinect_image)

image_transport::Subscriber sub = it.subscribe("camera/rgb/image_color", 1, imageCallback); or image_transport::Subscriber sub = it.subscribe("camera/depth/image", 1, imageCallback);

I dont know how can I get both the rgb and depth image in the callback funtion. The below way doesn't work.

void imageCallback(const sensor_msgs::ImageConstPtr& kinect_image,const sensor_msgs::ImageConstPtr& depth_image)

image_transport::Subscriber sub = it.subscribe("camera/rgb/image_color","camera/depth/image", 1, imageCallback);

I know, may be the question sounds very naive. But, I would really be grateful if someone can guide me.


Originally posted by Subhasis on ROS Answers with karma: 31 on 2012-10-18

Post score: 0

$\endgroup$

2 Answers 2

0
$\begingroup$

Rosanswers logo

The simplest solution is to create two different image callbacks as methods of a class and store the images in member variables when they are received.

A better solution is to use a synchronizer provided by the message_filters package. Have a look at the TimeSynchronizer example.


Originally posted by Lorenz with karma: 22731 on 2012-10-19

This answer was ACCEPTED on the original site

Post score: 5


Original comments

Comment by aguadopd on 2016-03-08:
If anyone reads this...Do we need to sync if the images are from the same device, say a kinect?

Comment by aguadopd on 2016-05-09:
Well, we needed indeed. After synchronising, offeset became lower. ROS Indigo Node for saving color and depth images from a Kinect

$\endgroup$
0
$\begingroup$

Rosanswers logo

Sample code. This is a ROS Indigo node for saving depth and color images from a Kinect - originally in a Turtlebot. Source, usage and more

/* Este es un nodo de ROS Indigo para guardar imagenes de /camera/depth_registered/image_rect_raw
 * y de /camera/rgb/color/image_rect_raw de un Turtlebot1 para luego procesarlas con otro programa. 
 * Las de profundidad se guardan como unsigned int de 16 bits 
 * y 1 canal, las de color se guardan como unsigned int de 8 bits en 3 canales.
 * Se utiliza un suscriptor sincronizado para guardar el par de imagenes que estén más
 * cercanas en el tiempo.
 * LAS IMAGENES SE GUARDAN ADONDE SE EJECUTE EL NODO.
 * ---------------------------------------------------------
 * Creado por Fabricio Emder y Pablo Aguado en el 2016 */


/* This is a ROS Indigo node for saving Turtlebot images from the /camera/depth_registered/image_rect_raw
 * and /camera/rgb/color/image_rect_raw topics, for further processing outside of the program. 
 * Depth images are saved as 1 channel 16 bit unsigned int PNGs (CV_16UC1), and 
 * RGB images are saved as 3 channel 8 bit unsigned int PNGs (CV_8UC3).
 * A synchronized subscriber is used, for saving the pair of images that are most closer in time.
 * THE IMAGES ARE SAVED WHEREVER THE NODE IS RUN.
 * Created by Fabricio Emder and Pablo Aguado - 2016
 * */

#include <ros/ros.h>
#include <cv_bridge/cv_bridge.h>    // OpenCV
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>

#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>


/* La política de sincronización exacta NO FUNCIONA para los topics seleccionados, ya 
 * que la Kinect o sus drivers no los están publicando con la misma marca temporal.
 * Ver más en http://wiki.ros.org/message_filters 
 * 
 * Exact sychronization policy IS NOT WORKING for the topics used, because the kinect
 * is not publishing them with the same timestamp. 
 * See more in http://wiki.ros.org/message_filters  */

//#define EXACT
#define APPROXIMATE


#ifdef EXACT
#include <message_filters/sync_policies/exact_time.h>
#endif
#ifdef APPROXIMATE
#include <message_filters/sync_policies/approximate_time.h>
#endif

 
 
using namespace std;
//using namespace sensor_msgs;
using namespace message_filters;


// Contador para la numeración de los archivos.
// Counter for filenames.
unsigned int cnt = 1;



// Handler / callback
void callback( const sensor_msgs::ImageConstPtr& msg_rgb , const sensor_msgs::ImageConstPtr& msg_depth )
{
        //ROS_INFO_STREAM("Adentro del callback\n");
      cv_bridge::CvImagePtr img_ptr_rgb;
        cv_bridge::CvImagePtr img_ptr_depth;
    try{
        img_ptr_depth = cv_bridge::toCvCopy(*msg_depth, sensor_msgs::image_encodings::TYPE_16UC1);
    }
    catch (cv_bridge::Exception& e)
    {
        ROS_ERROR("cv_bridge exception:  %s", e.what());
        return;
    }
    try{
        img_ptr_rgb = cv_bridge::toCvCopy(*msg_rgb, sensor_msgs::image_encodings::TYPE_8UC3);
    }
    catch (cv_bridge::Exception& e)
    {
        ROS_ERROR("cv_bridge exception:  %s", e.what());
        return;
    }

    cv::Mat& mat_depth = img_ptr_depth->image;
        cv::Mat& mat_rgb = img_ptr_rgb->image;
        
        char file_rgb[100];
        char file_depth[100];
        
        sprintf( file_rgb, "%04d_rgb.png", cnt );
        sprintf( file_depth, "%04d_depth.png", cnt );
        
        vector<int> png_parameters;
        png_parameters.push_back( CV_IMWRITE_PNG_COMPRESSION );
        /* We save with no compression for faster processing.
         * Guardamos PNG sin compresión para menor retardo. */
        png_parameters.push_back( 9 ); 
        
        cv::imwrite( file_rgb , mat_rgb, png_parameters );
        cv::imwrite( file_depth, mat_depth, png_parameters );
        
        ROS_INFO_STREAM(cnt << "\n");
        ROS_INFO_STREAM("Imágenes guardadas - "
                        "Images saved\n");
        
        cnt++;
        
}





int main(int argc, char** argv)
{
    // Initialize the ROS system and become a node.
  ros::init(argc, argv, "guardar_imagenes");
  ros::NodeHandle nh;
    
    
    message_filters::Subscriber<sensor_msgs::Image> subscriber_depth( nh , "/camera/depth_registered/hw_registered/image_rect_raw" , 1 );
    message_filters::Subscriber<sensor_msgs::Image> subscriber_rgb( nh , "/camera/rgb/image_rect_color" , 1 );

    
#ifdef EXACT
    typedef sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image> MySyncPolicy;
#endif
#ifdef APPROXIMATE
    typedef sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> MySyncPolicy;
#endif
    
    
  // ExactTime or ApproximateTime take a queue size as its constructor argument, hence MySyncPolicy(10)
  Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), subscriber_rgb, subscriber_depth );
  sync.registerCallback(boost::bind(&callback, _1, _2));

    
    while(ros::ok())
    {
        char c;
        
        ROS_INFO_STREAM("\nIngrese 'a' para guardar un par de imágenes o 'b' para guardar 300 imágenes\n"
                        "Enter 'a' to save a pair of images or 'b' to automatically save 300 images\n");
        cin.get(c);
        cin.ignore();
        c = tolower(c);
        ROS_INFO_STREAM("You entered " << c << "\n");
        
        if( c == 'a' )
        {
                /* Le damos el control a la función callback cuando haya imágenes.
                * We give control to the callback function.*/
                ros::spinOnce();    
        }
        
        else if( c == 'b' )
        {
            unsigned int cnt_init = cnt;
            while( cnt - cnt_init < 300 )
            {
                ros::spinOnce();
            }
        }
        
        else break;

    }
    ROS_INFO_STREAM("Cerrando nodo\nClosing node\n");

  return 0;
}

Originally posted by aguadopd with karma: 86 on 2016-05-09

This answer was NOT ACCEPTED on the original site

Post score: 2


Original comments

Comment by Maverobot on 2018-04-27:
I don't get it why such a good answer did not get upvotes.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.