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

Turtlebot depth image not showing in image_view

asked 2014-03-01 12:11:03 -0500

aguadopd gravatar image

updated 2016-10-24 09:08:04 -0500

ngrennan gravatar image

Hello,

I want to try some opencv algorithms with depth images from the turtlebot1 (create base). I want to save them for later use because of the complexity of modifying and remaking a node.

We have our Turtlebot started with Turtlebot_bringup minimal.launch and turtlebot_bringup 3dsensor.launch. RVIZ is currently showing /camera/depth_registered/image_raw (which dont look as detailed as I imagined looking at the IR image) but not any /camera/depth/ topic. I tried rostopic hz /camera/depth/image_raw but it is not publishing. rosrun image_view image_view image:=/camera/depth_registered/image_raw says:

Unable to convert '16UC1' image to bgr8: '[16UC1] is not a color format. but [bgr8] is. The conversion does not make sense'

Can I somehow easily save these images for later processing?

edit retag flag offensive close merge delete

3 Answers

Sort by » oldest newest most voted
1

answered 2014-03-01 18:00:14 -0500

domikilo gravatar image

Because data format in image_raw is the depth data in mm, maybe you should try with the /camera/depth/image If you want to use the image_raw, I think the below codes is helpful for you

void imageCb_d(const sensor_msgs::ImageConstPtr& msg)
  {

    cv_bridge::CvImagePtr cv_ptr;


    try
    {
      cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::TYPE_32FC1);

    }
    catch (cv_bridge::Exception& e)
    {
      ROS_ERROR("cv_bridge exception: %s", e.what());
      return;
    }




    double minVal, maxVal;
    minMaxLoc(cv_ptr->image, &minVal, &maxVal); //find minimum and maximum intensities
    //Mat draw;
    cv_ptr->image.convertTo(blur_img, CV_8U, 255.0/(maxVal - minVal), -minVal * 255.0/(maxVal - minVal));



    cv::imshow("Blur", blur_img);
    cv::imshow("Depth", cv_ptr->image);


    cv::waitKey(3);

    image_pub_.publish(cv_ptr->toImageMsg());
  }

};
edit flag offensive delete link more

Comments

Thank you! will try that. I will try using the 32bit part, since I don't want to lose resolution using 8 bit format.

aguadopd gravatar image aguadopd  ( 2014-03-04 07:51:18 -0500 )edit
0

answered 2018-06-07 09:17:10 -0500

Void gravatar image

I had a very similar problem. I was getting the error

Unable to convert '16UC1' image to bgr8: '[16UC1] is not a color format. but [bgr8] is. The conversion does not make sense'

because I was storing images from 2 different topics in a global variable. So although it seems data is retrieved from only 1 topic, it might be getting retrieved from 2.

edit flag offensive delete link more
0

answered 2016-05-09 18:37:56 -0500

aguadopd gravatar image

Based on @domikilo 's answer and some other sources, we wrote a node for saving both color and depth images from the Turtlebot. Source and usage.

I copy here, for future fast reference.

/* 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 ...
(more)
edit flag offensive delete link more

Comments

can you help me? the code don't save the image, the code runs perfectly, I select the option 'a' for to save the picture, and it continues to running, without save nothing. I used 'roswtf' and told me that subscribers nodes are disconnected

Jluis619 gravatar image Jluis619  ( 2016-06-03 11:16:33 -0500 )edit

Can you tell me how you called the callback from main? I am quite new and dont know how the callback is taking two param for msg_depth and msg_rgb

rasoo gravatar image rasoo  ( 2016-10-19 16:49:23 -0500 )edit

@rasoo The callback function is automatically called whenever there is one new message of any of the topics your node is subscribed to. So you have to subscribe to the topic, create a callback function, and then the magic is happening in the ros::ok() + ros::spinOnce() loop.

aguadopd gravatar image aguadopd  ( 2016-10-26 16:04:24 -0500 )edit

In this case the same callback function is used for two different messages. I don't remember is this is always possible or only because of the synchronizer.

aguadopd gravatar image aguadopd  ( 2016-10-26 16:08:28 -0500 )edit

Probably because of the synchronizer and
Synchronizer<mysyncpolicy> sync(MySyncPolicy(10), subscriber_rgb, subscriber_depth ); sync.registerCallback(boost::bind(&callback, _1, _2))

aguadopd gravatar image aguadopd  ( 2016-10-26 16:08:52 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-03-01 12:11:03 -0500

Seen: 5,578 times

Last updated: Jun 07 '18