It most likely is the case that your publisher is publishing your message before any subscribers to that message have been connected. It takes a "non-zero" amount of time for the "hand-shaking" to occur through the ROS master and between the publisher/subscriber nodes. You can write a section of code that will wait for a subscriber, publish the message (to that subscriber) then shut down the node. If you immediately shutdown a node after calling publish on a publisher it is not guaranteed that the message was sent and received by the subscriber.
A convenient overload to the advertise
function provided by the NodeHandle
class allows a client to specify a SubscriberStatusCallback
function pointer that gets called when a new subscriber connects to the publisher see the rosdocs.
Here is a simple code example with a std_msgs/String
topic:
#include <std_msgs/String.h>
#include <ros/ros.h>
void subscriberConnectCallback(const ros::SingleSubscriberPublisher& publisher)
{
ROS_INFO("Super cool I got a new subscriber [%s] on the %s topic!", publisher.getSubscriberName().c_str(),
publisher.getTopic().c_str());
// Build the message and publish
std_msgs::String msg;
msg.data = "super cool";
publisher.publish(msg);
// Signal shutdown
ros::shutdown();
}
int main(int argc, char* argv[])
{
ros::init(argc, argv, "test_node");
// Create publisher with private node handle and bind callback to handle subscriber connection
ros::NodeHandle pnh("~");
ros::Publisher publisher =
pnh.advertise<std_msgs::String>("chatter", 1, (ros::SubscriberStatusCallback)subscriberConnectCallback);
// Spin this node until a shutdown is triggered
ros::spin();
return 0;
}
We don't know what your code looks like and what message you are trying to publish and where. Please post your code, at least a snippet, so we can get context. Also, please be more detailed in your question. What have you tried so far and what errors you are facing (if any)!