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

first image message does not get published

asked 2011-10-21 02:26:52 -0500

JFReuter gravatar image

updated 2011-10-21 03:37:54 -0500

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);
}
edit retag flag offensive close merge delete

Comments

It would be much easier to debug this if you could post your code (or a link to it).
Eric Perko gravatar image Eric Perko  ( 2011-10-21 02:27:51 -0500 )edit
I have added a small example.
JFReuter gravatar image JFReuter  ( 2011-10-21 02:35:40 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
5

answered 2011-11-18 05:52:29 -0500

Wim gravatar image

After you create a ros publisher, it will take some time before the connections to all the subscribers are created. So when you publish a message right after you create the publisher, the message will not reach the subscribers. In your example, this is exactly what happens, when you create a new publisher in the first callback, and immediately publish a message. The second time you publish a message form the same callback, the connections are established and the messages will reach the subscribers.

edit flag offensive delete link more

Comments

2

Is there a way to check if the connection has been set up?

rhololkeolke gravatar image rhololkeolke  ( 2013-03-25 17:59:31 -0500 )edit

One way is to wait until pub.get_num_connections() > 0.

mbinna gravatar image mbinna  ( 2017-10-17 23:08:10 -0500 )edit
0

answered 2017-07-29 05:35:58 -0500

rubanraj54 gravatar image

updated 2017-07-29 05:36:24 -0500

I also face the same issue, when i publish the message, the subscriber always missed the first message. The reason was already answered by @Wim and it was correct.

To solve this issue, i used sleep() method with some milliseconds after publisher creation. So, meanwhile the publisher will make connection with all waiting subscribers. Then, you can start publishing message, and subscriber will receive all messages.

pub = rospy.Publisher('counter',Int32,queue_size=10)

rate = rospy.Rate(2)

rate.sleep() #sleep for 500ms

counter = 1;

while not rospy.is_shutdown():
    pub.publish(counter)
    counter += 1
    rate.sleep()
edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-10-21 02:26:52 -0500

Seen: 1,785 times

Last updated: Jul 29 '17