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

subscriber callback unable to access class member

asked 2013-10-01 05:08:50 -0500

thebyohazard gravatar image

I'm not really sure if this is a ROS problem or a C++ problem, but it's blowing my mind.

  • I have a class with a vector of structs in it.
  • I construct some structs and push_back them into the vector
  • In the constructor of the struct, I create a subscriber
  • The callback of this subscriber is a member function of the struct.
  • The subscriber successfully gets called when a message is published, but the callback doesn't have valid member data.

My question is: what is going on here? I know a few quick ways to solve the problem, but they're kind of cheating, and anyway, I want to understand. I'm thinking it's either that I'm unaware of some threading issue ros is doing behind the scenes, or the this pointer isn't getting correctly to the subscriber. But I've tried everything I could think to do.

Here's a minimal example like what I'm trying to do:

#include <ros/ros.h>
#include <std_msgs/Bool.h>

struct S{
    ros::NodeHandle n;
    ros::Subscriber subscriber;
    unsigned int _number;

    S(std::string topic_name, unsigned int number){
        _number = number;
        ROS_INFO("the number is %i",_number);   //prints out as 5
        subscriber = n.subscribe<std_msgs::Bool>(topic_name, 1, &S::S_cb, this);
    }
    void S_cb(const std_msgs::Bool::ConstPtr &msg){
        ROS_INFO("performing foo on %i", _number);   //prints out as 0 - why???
        //foo(_number, msg->data);
    }
};

class TestNode{
  ros::NodeHandle n;
  std::vector<S> s_array;

public:
  TestNode(std::string name){
    s_array.push_back(S("test_topic",5));
  }
  ~TestNode(){ }
};

int main(int argc, char *argv[]){
  ros::init(argc, argv, "test_node");

  TestNode tn(ros::this_node::getName());

  ros::spin();
  return 0;
}
edit retag flag offensive close merge delete

Comments

Does this compile? Shouldn't S need a S() constructor to be put into a vector?

dornhege gravatar image dornhege  ( 2013-10-01 05:15:43 -0500 )edit

I didn't compile the above test case (probably should have...), but the real code it's based on compiles fine. Anyway, according to [cplusplus.com](http://www.cplusplus.com/reference/vector/vector/vector/), this way to initialize a vector creates a vector of 0 S elements, so no Ss are constructed until push_back happens

thebyohazard gravatar image thebyohazard  ( 2013-10-01 05:28:46 -0500 )edit

Doesn't matter. You can still call resize(n) that will default construct n elements. My guess is this should give a compile error.

dornhege gravatar image dornhege  ( 2013-10-01 05:49:29 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2013-10-01 05:19:28 -0500

dornhege gravatar image

Just a guess, someone that knows the internals can determine this more clearly: This has to do with the fact that a vector inserts by copying values. Before you push_back a temporary is created, which the subscriber is initialized with (including this pointer). This is copied into the vector - the resulting object in the vector has a different this pointer, but the subscriber is copied by value - it can't know the new this pointer. Then the temporary is destroyed and you get random memory when in the callback.

Proper fix for this: Make a copy-constructor + maybe assignment operator that re-initializes the subscriber.

edit flag offensive delete link more

Comments

This makes perfect sense, and using a copy-constructor fixes the problem. I should have read [push_back](http://www.cplusplus.com/reference/vector/vector/push_back/) more carefully.

thebyohazard gravatar image thebyohazard  ( 2013-10-01 05:58:35 -0500 )edit
0

answered 2013-10-01 06:02:01 -0500

thebyohazard gravatar image

For posterity, it should be noted that emplace_back will create an element at the end of a vector, rather than just copying it as push_back does. This is a bit easier in my case than making a copy-constructor as @dornhege says, but it's C++11 only, and the copy-constructor does in fact work.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2013-10-01 05:08:50 -0500

Seen: 1,168 times

Last updated: Oct 01 '13