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

publish an array of images

asked 2011-05-18 22:05:47 -0500

Yianni gravatar image

Hi,

I am trying to publish an array of images. Looking at ros wiki I couldn't find something relevant... I am attaching below my code... The publishing of the array should be at the "try" clause. Any help or hints would be appreciated.

Thanks.

#include "boost/filesystem.hpp"
#include "sensor_msgs/Image.h"
#include "image_transport/image_transport.h"
#include "cv_bridge/CvBridge.h"
#include "std_msgs/String.h"

#include <iostream>
#include <string>
#include <vector>
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include <ros/ros.h>
#include <signal.h>

using namespace boost::filesystem;
using namespace std;

void ctrlc(int s)
{
    cout << "ctrl-c pressed" << endl;
    ros::shutdown();
    signal(SIGINT, SIG_DFL);
}

int main(int argc, char *argv[])
{
    ros::init(argc, argv, "Static_Image_Publisher");
    ros::NodeHandle n;
    image_transport::ImageTransport it_(n);
    sensor_msgs::CvBridge bridge_;
    image_transport::Publisher image_pub_;
    image_pub_ = it_.advertise("/camera_sim/image_raw", 1);
    int cvDelay = (argc == 2 ? atoi(argv[1]) : 500);
    string p(argc == 3 ? argv[2] : ".");
    vector<string> filenames;
    IplImage *img = NULL;
    vector<IplImage*> imgs;

    if (is_directory(p))
        for (directory_iterator itr(p); itr!=directory_iterator(); ++itr)
            if (is_regular_file(itr->status())) {
                string str(itr->path().file_string());
                filenames.push_back(str);
            }

    sort(filenames.begin(), filenames.end());
    signal(SIGINT, ctrlc);
    for(;;) {
        imgs.clear();
        for (vector<string>::iterator itr = filenames.begin(); itr != filenames.end(); ++itr) {
            img = cvLoadImage(itr->c_str());
            imgs.push_back(img);
        }
        try {
            cout << ".\n";
            // publishes one image at a time, how would I publish the array of images
            //image_pub_.publish(bridge_.cvToImgMsg(imgs[0], "bgr8"));
        } catch (sensor_msgs::CvBridgeException error) {
            ROS_ERROR("error");
        }
    }

    ros::spin();
    return 0;
}
edit retag flag offensive close merge delete

Comments

If you use while(ros::ok()) in your main loop, you don't need to signal handler yourself.
dornhege gravatar image dornhege  ( 2011-05-18 22:34:05 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
0

answered 2011-05-19 04:15:56 -0500

Yianni gravatar image

updated 2011-05-19 19:56:14 -0500

The following publishes an array of images read from a directory.

#include "boost/filesystem.hpp"
#include "sensor_msgs/Image.h"
#include "image_transport/image_transport.h"
#include "cv_bridge/CvBridge.h"
#include "std_msgs/String.h"
#include "Static_Image_Publisher/ArrayImages.h"

#include <iostream>
#include <string>
#include <vector>
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include <ros/ros.h>
#include <signal.h>

using namespace boost::filesystem;
using namespace std;

void ctrlc(int s)
{
    cout << "ctrl-c pressed" << endl;
    ros::shutdown();
    signal(SIGINT, SIG_DFL);
}

int main(int argc, char *argv[])
{
    ros::init(argc, argv, "static_image_publisher_publish_list");
    ros::NodeHandle n;
    ros::Publisher pub = n.advertise<Static_Image_Publisher::ArrayImages>("/list_of_rois", 1000, true);
    sensor_msgs::CvBridge bridge_;
    int cvDelay = (argc == 2 ? atoi(argv[1]) : 30000);
    string p(argc == 3 ? argv[2] : ".");
    vector<string> filenames;
    vector<IplImage*> imgs;
    Static_Image_Publisher::ArrayImages rosimgs;

    if (is_directory(p))
        for (directory_iterator itr(p); itr!=directory_iterator(); ++itr)
            if (is_regular_file(itr->status())) {
                string str(itr->path().file_string());
                filenames.push_back(str);
            }

    sort(filenames.begin(), filenames.end());
    signal(SIGINT, ctrlc);
//  cvNamedWindow("main", CV_WINDOW_AUTOSIZE);
//  cvMoveWindow("main", 600, 600);
    for(;;) {
        cout << ".\n";
        for (uint i=0; i<imgs.size(); i++)
            cvReleaseImage(&(imgs[i]));
        imgs.clear();
        for (vector<string>::iterator itr = filenames.begin(); itr != filenames.end(); ++itr) {
            imgs.push_back(cvLoadImage(itr->c_str()));
//          cvShowImage("main", imgs[imgs.size()-1]);
//          cvWaitKey(1000);
        }
        rosimgs.data.clear();
            // header of rosimgs ignored for now
        for (uint i=0; i<imgs.size(); i++) {
            try {
                rosimgs.data.push_back(*(bridge_.cvToImgMsg(imgs[i], "bgr8")));
            } catch (sensor_msgs::CvBridgeException error) {
                ROS_ERROR("error");
            }
        }
        pub.publish(rosimgs);
        cvWaitKey(cvDelay);
    }

    ros::spin();
    return 0;
}

Using the following simple message:

 Header header
 sensor_msgs/Image[] data
edit flag offensive delete link more

Comments

That should do it!
dornhege gravatar image dornhege  ( 2011-05-19 05:40:46 -0500 )edit
2

answered 2011-05-18 22:31:44 -0500

dornhege gravatar image

You need a message that holds an Image array. I don't know if there is one, if not it is very easy to define one yourself.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-05-18 22:05:47 -0500

Seen: 2,907 times

Last updated: May 19 '11