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

Callback with "this"

asked 2013-06-27 11:19:07 -0500

Zayin gravatar image

I'm trying to call a callback function with a "this" pointer in the following way:

ros::Subscriber sub = node.subscribe("map_metadata", 1, &Obstacle::metaDataCallback, this);

The Callback function is:

//Get the occupancy grid metadata.
void Obstacle::metaDataCallback(const nav_msgs::MapMetaData::ConstPtr& msg) {       
        this->width = msg->width;
        this->height = msg->height;
        this->resolution = msg->resolution;
}

When I try to print the width, height and resolution of "this" after the callback has returned, the values are always 0 (as when initialized). However, I know they should be 288, 288 and 0.1 respectively. Why aren't the parameters properly stored in "this"? How can I make it so?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2013-06-27 18:25:33 -0500

Check a few things that could be wrong:

  • Is your callback actually being called?
    • add a print statement in the callback to make sure
    • check rqt_graph to see if your node is actually subscribed to the topic
  • Does your "Obstacle" object go out of scope?
  • Does the subscriber object (sub) go out-of-scope?
  • Did you remember to call 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}"
edit flag offensive delete link more

Comments

Thanks so much for your answer! I'm new to programming Callbacks and in C++, so my code is different and not well structured. It is not working despite the fact that I did use rosSpin, that the Callback is being called, etc. I don't know what the problem is, so I'll use your code as a basis instead!

Zayin gravatar image Zayin  ( 2013-06-28 05:13:03 -0500 )edit
1

I would encourage you to not just drop your old code. Try to compare what works and doesn't work to find out where the problem is. That's the only way you'll learn!

Jeremy Zoss gravatar image Jeremy Zoss  ( 2013-06-28 05:30:44 -0500 )edit

I got it to work based on your code. Thanks again!

Well it's too late now. One thing that was different is that I was calling "spin" from within a method of obstacle instead of doing that in main. Moreover I had no while loop. Then maybe I was printing the values before actually setting them.

Zayin gravatar image Zayin  ( 2013-06-28 06:39:44 -0500 )edit

Hi Zayin. I am wondering, if the "width" and "height" in MapMetaData is referring to the width and height of the entire map, or the individual cell in the entire map?

Gazer gravatar image Gazer  ( 2013-08-17 07:03:14 -0500 )edit

I supposed you had a look at this: http://www.ros.org/doc/api/nav_msgs/html/msg/MapMetaData.html. They're parameters for the entire map, while the cell size is determined by its resolution afaik.

Zayin gravatar image Zayin  ( 2013-08-26 05:00:49 -0500 )edit

Question Tools

Stats

Asked: 2013-06-27 11:19:07 -0500

Seen: 1,206 times

Last updated: Jun 27 '13