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

Revision history [back]

click to hide/show revision 1
initial version

We see this:

void dijkstra(const nav_msgs::OccupancyGrid& map)
{
  ...

  ros::NodeHandle n("~");
  ros::Publisher pose_array_pub = n.advertise<geometry_msgs::PoseArray>("/poseArray", 1);
  pose_array_pub.publish(poseArray);
}

Never create NodeHandles, ros::Publisher or ros::Subscribers in the body of callbacks or in short-lived functions.

It will not work.

Also never call publish(..) immediately after constructing a ros::Publisher. There is no time for Subscribers to actually subscribe, so no one receives your message.

Create them in your main(..) and pass them to your callback. Or create them as global variables or create a class and store them as members.

We see this:

void dijkstra(const nav_msgs::OccupancyGrid& map)
{
  ...

  ros::NodeHandle n("~");
  ros::Publisher pose_array_pub = n.advertise<geometry_msgs::PoseArray>("/poseArray", 1);
  pose_array_pub.publish(poseArray);
}

Never create NodeHandles, ros::Publisher or ros::Subscribers in the body of callbacks or in short-lived functions.

It will not work.

Also never call publish(..) immediately after constructing a ros::Publisher. There is no time for Subscribers to actually subscribe, so no one receives your message.

Create them in your main(..) and pass them to your callback. Or create them as global variables or create a class and store them as members.

Then if you're only publishing the message once, make sure there are subscribers. You can use ros::Publisher::getNumSubscribers() for this. But if only publishing once and it's important your message always arrives, then I would suggest to use a service instead of a topic.

We see this:

void dijkstra(const nav_msgs::OccupancyGrid& map)
{
  ...

  ros::NodeHandle n("~");
  ros::Publisher pose_array_pub = n.advertise<geometry_msgs::PoseArray>("/poseArray", 1);
  pose_array_pub.publish(poseArray);
}

Never create NodeHandles, ros::Publisher or ros::Subscribers in the body of callbacks or in short-lived functions.

It will not work.

Also never call publish(..) immediately after constructing a ros::Publisher. There is no time for Subscribers to actually subscribe, so no one receives your message.

Create them in your main(..) and pass them to your callback. Or create them as global variables or create a class and store them as members.

Then if you're only publishing the message once, make sure there are subscribers. You can use ros::Publisher::getNumSubscribers() for this. But if only publishing once and it's important your message always arrives, then I would suggest to use a service instead of a topic.


Edit:

Okay, yes. I made a publisher in mainand then I declared a global poseArray and then published it in a loop something like this -

while(ros::ok())
{
  pose_array_pub.publish(pa);
}

I would strongly recommend you do not do this. For two reasons (at leat):

  1. you're not publishing many, many old messages as pa is not updated before publish(..) is called
  2. if this is the exact code you used: you're publishing at the maximum rate at which your PC can publish (which for a typical PC is upwards of 10kHz)

What I was actually suggesting was something like this:

#include <ros/ros.h>

...

ros::Publisher pub;   // note: in global scope here

...

void dijkstra(const nav_msgs::OccupancyGrid& map)
{
  ...

  // use variable in global scope
  pub.publish(poseArray);
}


int main(int argc, char **argv)
{
  ros::init(argc, argv, "dijkstra");
  ros::NodeHandle n("~");
  ...

  // initialise variable in global scope
  pub = n.advertise<geometry_msgs::PoseArray>("/poseArray", 1);

  ...
  ros::spin();
}

We see this:

void dijkstra(const nav_msgs::OccupancyGrid& map)
{
  ...

  ros::NodeHandle n("~");
  ros::Publisher pose_array_pub = n.advertise<geometry_msgs::PoseArray>("/poseArray", 1);
  pose_array_pub.publish(poseArray);
}

Never create NodeHandles, ros::Publisher or ros::Subscribers in the body of callbacks or in short-lived functions.

It will not work.

Also never call publish(..) immediately after constructing a ros::Publisher. There is no time for Subscribers to actually subscribe, so no one receives your message.

Create them in your main(..) and pass them to your callback. Or create them as global variables or create a class and store them as members.

Then if you're only publishing the message once, make sure there are subscribers. You can use ros::Publisher::getNumSubscribers() for this. But if only publishing once and it's important your message always arrives, then I would suggest to use a service instead of a topic.


Edit:

Okay, yes. I made a publisher in mainand then I declared a global poseArray and then published it in a loop something like this -

while(ros::ok())
{
  pose_array_pub.publish(pa);
}

I would strongly recommend you do not do this. For two reasons (at leat):least):

  1. you're not publishing many, many old messages as pa is not updated before publish(..) is called
  2. if this is the exact code you used: you're publishing at the maximum rate at which your PC can publish (which for a typical PC is upwards of 10kHz)

What I was actually suggesting was something like this:

#include <ros/ros.h>

...

ros::Publisher pub;   // note: in global scope here

...

void dijkstra(const nav_msgs::OccupancyGrid& map)
{
  ...

  // use variable in global scope
  pub.publish(poseArray);
}


int main(int argc, char **argv)
{
  ros::init(argc, argv, "dijkstra");
  ros::NodeHandle n("~");
  ...

  // initialise variable in global scope
  pub = n.advertise<geometry_msgs::PoseArray>("/poseArray", 1);

  ...
  ros::spin();
}