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

How to subscribe to sensor_msgs/CompressedImage without the raw image?

asked 2016-03-29 18:58:45 -0500

Ralff gravatar image

Recently, I recorded a large set of image data using a rosbag, but I am not able to get the subscriber working for the compressed image topic. I did not save the image_raw topic. I only saved the compressed topic. These are the topics contained in my rosbag file.

/usb_cam/camera_info

/usb_cam/image_raw/compressed

I am able to extract the images from the bag file and save to disk using a command that looks something like this

rosrun image_view extract_images _sec_per_frame:=0.001 image:=/usb_cam/image_raw _image_transport:=compressed

I do want to note that the number of /usb_cam/image_raw/compressed messages in my bag file is 16078 and after executing that command the number of images saved to disk is only 16052

Regardless, the main issue is that I am not able to get the images through a subscriber in any of my nodes. I am able to get the images in my subscriber in real time using the image_raw topic, but I can't get this to work using only the compressed topic. I have looked at several tutorials, but I am still not able to figure it out. I think I am missing something very simple. Here is my code for the simple subscriber that will not work.

class Images
{
public:
    image_transport::Subscriber sub_image;these

    Images()
    {
            ros::NodeHandle node;
            image_transport::ImageTransport it(node);
            sub_image = it.subscribe("/usb_cam/image_raw/compressed", 1, &Images::imageCallback, this);
    }

    void imageCallback(const sensor_msgs::ImageConstPtr& msg)
    {
        try
        {
            cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
            cv::waitKey(30);
        }
        catch (cv_bridge::Exception& e)
        {
            ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());

        }

    }
};

int main(int argc, char **argv)
{
    ros::init(argc, argv, "my_node");
    ROS_INFO("my_node running...");
    Images images;
    ros::spin();
    return 0;
}

If I run this code I get the following error messages:

[ WARN] [1459295416.022612760]: [image_transport] It looks like you are trying to subscribe directly to a transport-specific image topic '/usb_cam/image_raw/compressed', in which case you will likely get a connection error. Try subscribing to the base topic '/usb_cam/image_raw' instead with parameter ~image_transport set to 'compressed' (on the command line, _image_transport:=compressed). See http://ros.org/wiki/image_transport for details.

I don't know how to subscribe to '/usb_cam/image_raw' instead because this topic does not exist in my rosbag file. If I do subscribe to '/usb_cam/image_raw', then the callback function never triggers because the topic doesn't exist. How do I do this?

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
2

answered 2017-07-25 09:33:43 -0500

wwfzs1990 gravatar image

To directly subscribe to sensor_msgs/CompressedImage and get the compressed image, you can do as the followings without the image_transport:

#include <ros/ros.h>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>

void imageCallback(const sensor_msgs::CompressedImageConstPtr& msg)
{
  try
  {
    cv::Mat image = cv::imdecode(cv::Mat(msg->data),1);//convert compressed image data to cv::Mat
    cv::imshow("view", image);

    cv::waitKey(10);
  }
  catch (cv_bridge::Exception& e)
  {
    ROS_ERROR("Could not convert to image!");
  }
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "image_listener");
  ros::NodeHandle nh;
  cv::namedWindow("view");
  cv::startWindowThread();
  ros::Subscriber sub = nh.subscribe("/usb_cam/image_raw/compressed", 1, imageCallback);
  ros::spin();
  cv::destroyWindow("view");
}
edit flag offensive delete link more

Comments

Thanx man..cheers

JeyP4 gravatar image JeyP4  ( 2019-03-13 15:58:24 -0500 )edit

I followed your method, but it has another error: “ ‘CompressedImageConstPtr’ in namespace ‘sensor_msgs’ does not name a type “. Do you have any idea how to fix it?

Felicity Pan gravatar image Felicity Pan  ( 2020-07-11 22:10:11 -0500 )edit
1

answered 2016-03-30 10:46:34 -0500

gvdhoorn gravatar image

Have you checked the relevant sections of the image_transport/Tutorials/ExaminingImagePublisherSubscriber tutorial? In particular 1.3 - Changing the Transport Used?

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-03-29 18:58:45 -0500

Seen: 17,958 times

Last updated: Mar 30 '16