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

Image publisher node publishes empty header

asked 2018-02-07 14:19:38 -0500

JKaiser gravatar image

I am trying to make a node that can both capture omnidirectional images to unwrap them and subsequently publish the resulting image in a new topic. As of now, the capturing of images for unwrapping works correctly (as I also save the resulting images in the robot's computer and they look as they should), but attempting to publish that result nets me a black rectangle where the unwrapped image should be.

The code of the node:

#include <opencv2/opencv.hpp>
#include <vector>
#include <string>
#include <sstream>
#include <cmath>
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>

double pi = 3.1415926535897932384626433832795;
int radius, valix, valiy, newx, newy;
double angular;
long numimage = 0;
std::string imcamino, nomfile;
std::ostringstream ss;
int interad = 229;
int exterad = 917;
int centerx = 613;
int centery = 490;

//Width and Height of the panoramic image
int widthdx = int(exterad*pi*2);
int heightdx = int(exterad - interad + 1);
cv::Mat image;
cv::Mat imdx(heightdx-1, widthdx-1, CV_8UC1); //Matrix to hold new image
cv_bridge::CvImageConstPtr imbuff; //Image buffer for ROS-OpenCV image conversion


void imageCallback(const sensor_msgs::ImageConstPtr& msg){ //Callback function to process and save panoramic images
    try{
        imbuff = cv_bridge::toCvCopy(msg, "mono8"); //Transforms ROS image to OpenCV image
    }
    catch(cv_bridge::Exception& e){
        ROS_ERROR("Could not convert from '%s' to 'mono8'.", msg->encoding.c_str()); //Error should the conversion fail
    }

    //Transform Omnidirectional image into a panoramic image
    for(valix = 0;valix < widthdx-1;valix++){
    angular = (valix*pi*2)/widthdx;
    for(valiy = 0;valiy < heightdx-1;valiy++){
        radius = int(interad + (heightdx - valiy));
        newx = int((radius*cos(angular)/2) + centerx);
        newy = int((radius*sin(angular)/2) + centery);
        imdx.at<uint8_t>(valiy,valix) = cv::Mat(imbuff->image).at<uint8_t>(newy,newx);
    }
    }
    //Save parameters
    cv::vector<int> compression_params;
    compression_params.push_back(CV_IMWRITE_JPEG_QUALITY);
    compression_params.push_back(100);
    //String for the filename
    ss << numimage;
    nomfile = ss.str();
    imcamino = "/home/p3at/datasetjorge/";
    imcamino += nomfile;
    imcamino += ".jpg";
    cv::imwrite(imcamino, imdx, compression_params); //Save image in the previously specified filepath
    numimage++;
    ss.str("");
    ss.clear();
}

int main(int argc, char **argv){
    ros::init(argc,argv,"image_storer");
    ros::NodeHandle nh;
    image_transport::ImageTransport it(nh);
    image_transport::Subscriber sub = it.subscribe("/image_raw", 1, imageCallback);
    image_transport::Publisher pub = it.advertise("/image_dewrapped", 1);
    sensor_msgs::ImagePtr msgf = cv_bridge::CvImage(std_msgs::Header(), "mono8", imdx).toImageMsg(); //Transforms OpenCV image to ROS Image Message
    while(nh.ok()){
        pub.publish(msgf); //Publish Image message in topic /image_dewrapped P.S.:Does not work properly
    }
    ros::spin();
}

the resulting "image" seen in image view:

image description

Any help to being able to view the unwrapped image?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-02-07 15:14:27 -0500

lucasw gravatar image

updated 2018-02-07 15:18:45 -0500

:

sensor_msgs::ImagePtr msgf = cv_bridge::CvImage(std_msgs::Header(), "mono8", imdx).toImageMsg(); //Transforms OpenCV image to ROS Image Message
while(nh.ok()){
    pub.publish(msgf); //Publish Image message in topic /image_dewrapped P.S.:Does not work properly
}

You need to convert the cv image to a ROS Image on every update to cv image ( http://docs.ros.org/kinetic/api/cv_br... says the underlying image data is copied).

You also should restructure so the while loop doesn't publish if the image hasn't been updated and won't have issues with multi-threading or single threading, the callback never gets a chance to get called if the while loop never sleeps, or if multithreading the callback may be in the middle of changing the message when the publish is called. One approach that ought to fix all of the above would be to publish at the end of the callback and use a ros msg and cv mat local to the callback, the publisher could be global.

See http://wiki.ros.org/roscpp/Overview/C...

edit flag offensive delete link more

Comments

Thank you so much. Your suggestion worked perfectly

JKaiser gravatar image JKaiser  ( 2018-02-10 10:56:43 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-02-07 14:19:38 -0500

Seen: 1,362 times

Last updated: Feb 07 '18