ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Check a few things that could be wrong:
rqt_graph
to see if your node is actually subscribed to the topicsub
) go out-of-scope?ros::spin()
?Here is some example code that works for me. See below for usage.
#include <ros/ros.h>
#include <nav_msgs/MapMetaData.h>
class Obstacle
{
public:
ros::Subscriber sub;
unsigned int width, height;
float resolution;
Obstacle() : width(0), height(0), resolution(0)
{
ros::NodeHandle node;
sub = node.subscribe("map_metadata", 1, &Obstacle::metaDataCallback, this);
}
void metaDataCallback(const nav_msgs::MapMetaData::ConstPtr &msg) {
this->width = msg->width;
this->height = msg->height;
this->resolution = msg->resolution;
}
};
int main(int argc, char **argv)
{
ros::init(argc, argv, "subTest");
Obstacle obs;
while (ros::ok())
{
ROS_INFO("width: %d, height: %d, resolution: %g",
obs.width, obs.height, obs.resolution);
ros::spinOnce();
sleep(2);
}
return 0;
}
Build this node and run it. It should start printing out the current member-variable states (all-zeros). Then, publish your message. It should start printing the new values, once the messages are received. For testing, I manually published a message:
$ rostopic pub "map_metadata" nav_msgs/MapMetaData "{width: 1, height: 2, resolution: 3.14159}"