first image message does not get published
I have a node that among many other things, publishes images for debugging purposes. However, this does not work all the time, and some messages never get seen by other nodes.
The messages get published from a subscription callback, if that makes a difference.
Symptoms:
- The first message never gets published
- Other messages (PointCloud2) work fine
- Messages don't get published, even when callback is idle
- cv_bridge or manual message creation makes no difference
- No error messages at all
I have verified that the publish method does get called, and even stepped into it. There does not seem to be a problem there.
I am at a loss. What could be the problem?
Edit :
#include <ros/publisher.h>
#include <ros/subscriber.h>
#include <ros/node_handle.h>
#include <sensor_msgs/Image.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/core/core.hpp>
std::map<std::string, ros::Publisher> mPublishers;
ros::Subscriber imgSub;
template <class msg_type>
ros::Publisher getPublisher(const std::string& topic)
{
if (mPublishers.find(topic) == mPublishers.end())
{
std::ostringstream ostr;
ostr << "/" << "dump" << "/" << topic;
ros::NodeHandle mNh;
mPublishers[topic] = mNh.advertise<msg_type> (ostr.str(), 0, true);
}
return mPublishers[topic];
}
void cb(const sensor_msgs::ImageConstPtr& image_msg)
{
ros::Time time = image_msg->header.stamp;
cv_bridge::CvImageConstPtr cvImage = cv_bridge::toCvShare(image_msg, "");
const cv::Mat& image = cvImage->image;
sensor_msgs::ImagePtr msg(new sensor_msgs::Image());
int numBytes = image.step * image.rows;
msg->data.resize(numBytes);
for (int i = 0; i < numBytes; ++i)
{
msg->data[i] = image.data[i];
}
msg->encoding = "rgb8";
msg->header.stamp = time;
msg->header.frame_id = image_msg->header.frame_id;
msg->height = image.rows;
msg->width = image.cols;
msg->step = image.step;
ros::Publisher pub = getPublisher<sensor_msgs::Image>("cascade_faces");
pub.publish(msg);
}
int main (int argc, char** argv)
{
// Initialize ROS
ros::init (argc, argv, "my_template_alignment");
ros::NodeHandle nh;
imgSub = nh.subscribe("/camera/rgb/image_rect_color", 1, cb);
std::cout << "ready!" << std::endl;
// Spin
ros::spin ();
return (0);
}