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

Publishing an image from disk

asked 2011-10-14 01:58:24 -0600

quimnuss gravatar image

Hi!

What's te best way to solely stream an image from disk? How do I convert from cv::Mat to proper ROS image message?

The relevant snippet would be:

cv_bridge::CvImagePtr cv_ptr;
cv_ptr->image = cv::imread(this->filename_);
image_pub_.publish(cv_ptr->toImageMsg());

How can the cv_bridge::CvImagePtr be initialized? The command above aborts at runtime as one would expect if the constructor requires something else. The error:

iri_simple_perception: /usr/include/boost/smart_ptr/shared_ptr.hpp:418: T* boost::shared_ptr< <template-parameter-1-1> >::operator->() const [with T = cv_bridge::CvImage]: Assertion `px != 0' failed.

Having a look at toCvCopyImpl seems a bit of an overkill ( http://www.ros.org/doc/api/cv_bridge/html/c++/cv__bridge_8cpp_source.html#l00200 ). So, any suggestions?

edit retag flag offensive close merge delete

6 Answers

Sort by ยป oldest newest most voted
4

answered 2011-10-14 03:20:28 -0600

cv_bridge::CvImagePtr is a pointer type that points to NULL by default. You have to allocate storage before you can actually use it, and the boost assertion catches the null pointer dereference.

Correct would be either something like

cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);

or

cv_bridge::CvImagePtr cv_ptr;
cv_ptr.reset (new cv_bridge::CvImage);

As a rule of thumb, every ROS type xxxPtr is a pointer type for xxx.

edit flag offensive delete link more

Comments

Yes, that looks more like what I was thinking of. There's, however, something I'm still missing: a fatal is reported by the publish(cv_ptr->toImageMsg()). 'Call to publish() on an invalid image_transport::Publisher'. I've tried both filling the header and encoding as well as leaving them blank.
quimnuss gravatar image quimnuss  ( 2011-10-14 03:30:35 -0600 )edit
I'll mark the question as unresolved, in case somebody steps up to this alternative approach.
quimnuss gravatar image quimnuss  ( 2011-10-16 22:38:55 -0600 )edit
1
Did you advertise the publisher properly? It is not sufficient just to declare a Publisher image_pub_, you must call ImageTransport::advertise() or something similar to get a valid Publisher object.
roehling gravatar image roehling  ( 2011-10-17 00:46:14 -0600 )edit
Yes, I did. image_transport::Publisher pub = imgtransport_.advertise("disk/image", 1);
quimnuss gravatar image quimnuss  ( 2011-10-18 00:45:43 -0600 )edit
There was a bug, it perfectly works now.
quimnuss gravatar image quimnuss  ( 2011-10-24 05:23:19 -0600 )edit
2

answered 2014-02-13 12:31:40 -0600

TFinleyosu gravatar image

updated 2014-02-13 12:34:20 -0600

Here is my example that I got working in Hydro

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

int main(int argc, char** argv)
{
  ros::init(argc, argv, "image_publisher");
  ros::NodeHandle nh;

    cv_bridge::CvImage cv_image;
    cv_image.image = cv::imread("/home/taylor/Pictures/face.jpg",CV_LOAD_IMAGE_COLOR);
    cv_image.encoding = "bgr8";
    sensor_msgs::Image ros_image;
    cv_image.toImageMsg(ros_image);

  ros::Publisher pub = nh.advertise<sensor_msgs::Image>("/static_image", 1);
  ros::Rate loop_rate(5);

  while (nh.ok()) 
  {
    pub.publish(ros_image);
    loop_rate.sleep();
  }
}
edit flag offensive delete link more

Comments

Thank you very much! This code is excellent!

sam gravatar image sam  ( 2015-07-13 01:10:40 -0600 )edit
1

answered 2011-10-14 02:19:12 -0600

John Hoare gravatar image

I've used the gscam driver to publish saved video files as a camera, and you can also use it to do snapshots, or really anything that gstreamer supports. You would be able to do what you want using this driver.

edit flag offensive delete link more

Comments

Would it work with a single still jpg image?
quimnuss gravatar image quimnuss  ( 2011-10-14 02:23:25 -0600 )edit
Sure, however you'll have to adjust the gstreamer pipeline to constantly publish the same image.
John Hoare gravatar image John Hoare  ( 2011-10-14 02:32:54 -0600 )edit
Looks good. Although I am not familiar with the syntax, I've managed to publish the image through gst-launch. I'll look into it to port it to the gscam config export definition. Or you do know what that would be?
quimnuss gravatar image quimnuss  ( 2011-10-14 02:36:31 -0600 )edit
It will be the same syntax as the gst-launch command. Store the command you used to the gst-launch (without the sink) to the environment variable GSCAM_CONFIG. See the wiki for details.
John Hoare gravatar image John Hoare  ( 2011-10-14 02:40:57 -0600 )edit
Indeed it works! Thanks!
quimnuss gravatar image quimnuss  ( 2011-10-14 02:48:24 -0600 )edit
0

answered 2011-10-14 03:13:25 -0600

quimnuss gravatar image

The solution from John Hoare works. Although the filename has to be established within an environment variable, which might be inconvinient. I do have a node that sets the filename through dynamic_reconfigure and reads the image with imread. The sole thing missing is how a cv::Mat can be transformed to a publishable image ros message. The ros wiki explains how to do so once we have a cv_bridge::CvImagePtr but it does not explain how to construct the CvImagePtr given a cv::Mat.

edit flag offensive delete link more

Comments

how can I convert from CvImagePtr to cv::Mat

Robot gravatar image Robot  ( 2014-10-07 03:49:15 -0600 )edit
0

answered 2014-12-19 08:14:11 -0600

lucasw gravatar image

This takes an image file name from a command line and publishes at desired rate:

https://github.com/lucasw/vimjay/blob...

Making it take the filename from a rostopic could be nice.

#!/usr/bin/env python
# Lucas Walter
# GNU GPLv3
# Load an image from disk and publish it repeatedly

import cv2
import numpy as np
import rospy
import sys
from sensor_msgs.msg import Image

if __name__ == '__main__': 
    rospy.init_node('image_publish')

    name = sys.argv[1]
    image = cv2.imread(name)
    #cv2.imshow("im", image)
    #cv2.waitKey(5)

    hz = rospy.get_param("~rate", 1)
    rate = rospy.Rate(hz)

    pub = rospy.Publisher('image', Image, queue_size=1)

    msg = Image()
    msg.header.stamp = rospy.Time.now()
    msg.encoding = 'bgr8'
    msg.height = image.shape[0]
    msg.width = image.shape[1]
    msg.step = image.shape[1] * 3
    msg.data = image.tostring()
    pub.publish(msg)

    while not rospy.is_shutdown():
        pub.publish(msg)
        rate.sleep()
edit flag offensive delete link more
0

answered 2012-06-13 00:21:11 -0600

tayyab gravatar image

updated 2012-06-13 00:22:19 -0600

@quimnuss you can do something like

cv::Mat image; // fill in image with your image data

CvImagePtr img_ptr;

image.copyto(img_ptr->image);

link text

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-10-14 01:58:24 -0600

Seen: 6,428 times

Last updated: Dec 19 '14