ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
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 NodeHandle
s, ros::Publisher
or ros::Subscriber
s 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 Subscriber
s 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.
2 | No.2 Revision |
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 NodeHandle
s, ros::Publisher
or ros::Subscriber
s 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 Subscriber
s 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.
3 | No.3 Revision |
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 NodeHandle
s, ros::Publisher
or ros::Subscriber
s 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 Subscriber
s 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):
pa
is not updated before publish(..)
is calledWhat 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();
}
4 | No.4 Revision |
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 NodeHandle
s, ros::Publisher
or ros::Subscriber
s 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 Subscriber
s 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):
pa
is not updated before publish(..)
is calledWhat 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();
}