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

Setting class method callback from within object (C++)

asked 2015-04-16 16:11:47 -0500

Jordan9 gravatar image

updated 2015-04-17 11:12:47 -0500

I have some object-oriented C++ code where I'm trying to create a subscriber in the constructor of the class, and that subscriber's callback function should be one of the class's functions. I have been following the relevant tutorial, but with using this instead of a variable pointing to the class object, but am stuck with an issue. When I use the code below, it compiles properly but whenever the callback is called, it uses default values for private class variables instead of the ones that the object should have.

class TestObject
{
    private:
        std::string _objectName;
        ros::Subscriber _testSubscriber;

    public:
        testCallback(const geometry_msgs::TransformStamped::ConstPtr& msg)
        {
                ROS_INFO("Callback made from object with name: -- %s --", _objectName.c_str());
        }

        TestObject(std::string objectName, ros::NodeHandle n)
        {
            _objectName = objectName;
            _testSubscriber = n.subscribe("topicName", 1, &TestObject::testCallback, this);
        }
}


static std::map<std::string, TestObject> testObjects;

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

    TestObject newObject("objname");
    testObjects["firstObject"] = newObject;

    ros::spin();

    return 0;
}

Now when a message is published on that topic, this node would output the following:

[INFO] [Timethingy]: Callback made from object with name: -- --

i.e. it will have an empty string, even though the string should have been set when the object was constructed.

In summary: the tutorial linked above assumes that a subsciption callback function inside a class is set from outside that class; how can I set it from inside an instance of the same class, while retaining access to all of that class instance's set variables?

edit retag flag offensive close merge delete

Comments

Does your Object exists at the time the callback is triggered? if you already left the Object, Ros ll generate a new one.

Did u tried it with a static std::string?

ReneGaertner gravatar image ReneGaertner  ( 2015-04-17 02:20:33 -0500 )edit

This seems to be a bug in your c++ code unrelated to ROS.

dornhege gravatar image dornhege  ( 2015-04-17 03:29:42 -0500 )edit
1

Please post the calling code as well.

georg l gravatar image georg l  ( 2015-04-17 04:43:31 -0500 )edit

@ReneGaertner the object should still exist, because it exists in a global static map (see my edit to the code in the OP). @Georg, I have updated the OP to show the calling code as well.

Jordan9 gravatar image Jordan9  ( 2015-04-17 11:13:45 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
4

answered 2015-04-18 04:29:02 -0500

Wolf gravatar image

updated 2015-04-19 05:29:05 -0500

Your code does not compile for some typing errors and issues (no return type of testCallback, missing ; behind class etc.). If you want to remove irrelevant parts of your code before posting it please assure your code still compiles and the issue persists!!

I have compiled your given code, commenting out all the map stuff and fixing the typing error and it worked as you expected. Passing this pointer to a subscriber is perfectly valid!

Another point where your code does not compille is

testObjects["firstObject"] = newObject;

This call requires a TestObject() like, i. e. arg less constructor for your class, which it does not have in the above version. You could replace it by

testObjects.insert( std::pair<std::string, TestObject>( "firstObject", newObject  ) );

In the above code which would have the same effect but would compile in the above version as it only requires a copy constructor (TestObject( const TestObject& rhs )) which is implizitly created by the compiler. I am not sure want you are doning in your real code, but storing the class in a std::map like this can cause the above issue. If you copy a class object of a class holding a subscriber using the default copy constructor (all stl containers do internally a lot of copying) it creates a flat copy of your object. All contained class members are copied. The subscriber, however contains a pointer to its implementation, where the pointer is copied but not the implementation. This means if you copy a ros::Subscriber object you will just have to Handles for the same subscription that calls into the first callback bind to it. In your case that is the first object you created, that setup the subscriber and gave it its own this pointer. I. e. if you create a subscriber in a class giving it the this pointer and then copy the created object the subscriber handle in the copied object will still call the callback with the this pointer of the object it was copied from. If the object it was copied from then goes out of scope this will cause undefined behaviour or seg faults or if there is occasionally a 0 at the point where it believes _objectName.c_str() should be it may result in the behaviour up there.

In short: If you have a class that has a subscriber and gives it "this" and you want to pass the created class object around or store it in stl containers, use boost::shared_ptr, like:

std::map<std::string, boost::shared_ptr< TestObject > > testObjects;

and then:

boost::shared_ptr< TestObject > newObject( new TestObject("objname", n) );
testObjects["firstObject"] = newObject;
edit flag offensive delete link more

Comments

Using the boost::shared_ptr was the answer. Thanks!

Jordan9 gravatar image Jordan9  ( 2015-04-23 15:27:16 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-04-16 16:11:47 -0500

Seen: 3,230 times

Last updated: Apr 19 '15