Robotics StackExchange | Archived questions

New in ROS - sensor_msgs/image in openCV

hello!

i'm a new user of ROS and i'm trying to get a video stream from a node into opencv I'm having a node publishing a sensor_msgs/image message to a topic. I would like to use this message into opencv to analyse the video stream.

I already make the cv_bridge tutorial. I think it's to complicated for me and I don't understand how to make it work.

Can someone help me to write a subscriber to that sensor_msgs/image and get it on opencv?

Thanks

Asked by Shaarkrat on 2018-10-03 09:41:49 UTC

Comments

Just to clarify, you already have the node publishing images and would like to see those images in a subscriber?! If so, did you publish the images using image_transport?

Asked by matheusns on 2019-01-31 22:19:32 UTC

I could add that cv_bridge is exactly what you need in this case. It is the mechanism to transfer images between ROS messages and OpenCV. I advise you to look at it again and understand how it works.

Asked by PeteBlackerThe3rd on 2019-02-01 06:54:17 UTC

Answers

A simple test that you can perform to ensure that everything is running properly with the image_transport is try to see your images through the image_view:

rosrun image_view image_view image:=<image topic>

If everything runs fine, try to run the following code:

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

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, "image_listener");
  ros::NodeHandle nh;
  cv::namedWindow("view");
  cv::startWindowThread();
  image_transport::ImageTransport it(nh);
  image_transport::Subscriber sub = it.subscribe("camera/image", 1, imageCallback);
  ros::spin();
  cv::destroyWindow("view");
}

If you prefer, just to improve your implementation time, you can build your visualizer in python as well:

import roslib; roslib.load_manifest('rbx1_vision')
import rospy
import sys
import cv2
import cv2.cv as cv
from sensor_msgs.msg import Image, CameraInfo
from cv_bridge import CvBridge, CvBridgeError
import numpy as np

class cvBridgeDemo():
    def __init__(self):
        self.node_name = "cv_bridge_demo"

        rospy.init_node(self.node_name)

        # What we do during shutdown
        rospy.on_shutdown(self.cleanup)

        # Create the OpenCV display window for the RGB image
        self.cv_window_name = self.node_name
        cv.NamedWindow(self.cv_window_name, cv.CV_WINDOW_NORMAL)
        cv.MoveWindow(self.cv_window_name, 25, 75)

        # Create the cv_bridge object
        self.bridge = CvBridge()

        # Subscribe to the camera image and depth topics and set
        # the appropriate callbacks
        self.image_sub = rospy.Subscriber("/camera/rgb/image_color", Image, self.image_callback)

        rospy.loginfo("Waiting for image topics...")

    def image_callback(self, ros_image):
        # Use cv_bridge() to convert the ROS image to OpenCV format
        try:
            frame = self.bridge.imgmsg_to_cv(ros_image, "bgr8")
        except CvBridgeError, e:
            print e

        # Convert the image to a Numpy array since most cv2 functions
        # require Numpy arrays.
        frame = np.array(frame, dtype=np.uint8)

        # Display the image.
        cv2.imshow(self.node_name, frame)

        # Process any keyboard commands
        self.keystroke = cv.WaitKey(5)
        if 32 <= self.keystroke and self.keystroke < 128:
            cc = chr(self.keystroke).lower()
            if cc == 'q':
                # The user has press the q key, so exit
                rospy.signal_shutdown("User hit q key to quit.")

    def cleanup(self):
        print "Shutting down vision node."
        cv2.destroyAllWindows()   

def main(args):       
    try:
        cvBridgeDemo()
        rospy.spin()
    except KeyboardInterrupt:
        print "Shutting down vision node."
        cv.DestroyAllWindows()

if __name__ == '__main__':
    main(sys.argv)

I hope I could help you, if some question arises, do not hesitate to ask me.

Asked by matheusns on 2019-01-31 22:28:59 UTC

Comments

Thank you!, very much = )

Asked by Andrew xXx on 2020-03-06 07:52:22 UTC

Hi, I have an pedestrian hog function, and want to get the opencv format image from the image_callback you write in python. I have already add my hog into the cvBridgeDemo class, but I do not see the publisher or something in the image_callback function. Can you kindly help me?

Asked by QZZZ on 2020-11-23 18:31:36 UTC