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

Unexplainable Segfault (double free) in templated Subscriber (polling)

asked 2012-11-12 03:39:59 -0500

rado0x54 gravatar image

updated 2014-01-28 17:14:14 -0500

ngrennan gravatar image

Hey ROS-Community,

I have a very weird error in the attached templated subscriber class, that happens very(!) seldom but is quite frustrating.

Class:

/*
 * GenericSubscriber.hpp
 *
 *  Created on: Feb 29, 2012
 *      Author: mriedel
 */

#ifndef GENERICSUBSCRIBER_HPP_
#define GENERICSUBSCRIBER_HPP_

#include <telekyb_defines/telekyb_defines.hpp>
#include <boost/thread/mutex.hpp>

#include <ros/node_handle.h>

namespace TELEKYB_NAMESPACE
{

template <class T_>
class GenericSubscriber {
protected:
    T_ lastMsg;
    boost::mutex lastMsgLock;

    // Subscriber
    ros::Subscriber sub;

    void msgCallback(boost::shared_ptr<T_ const> msg) {
        boost::mutex::scoped_lock(lastMsgLock);
        lastMsg = *msg; // copy
    }

public:
    GenericSubscriber(ros::NodeHandle handle, const std::string& topicName, int queue_size) {
        sub = handle.subscribe(topicName, queue_size, &GenericSubscriber<T_>::msgCallback, this);
    }

    virtual ~GenericSubscriber() {};

    T_ getLastMsg() const {
        boost::mutex::scoped_lock(lastMsgLock);
        return lastMsg; // implicit copy. Maybe we can do this more efficient?
    }
};

}

#endif /* GENERICSUBSCRIBER_HPP_ */

This class enables me to receive generic messages and save the last message in a variable and collect the message with getLastMsg() when needed. Very simple.

Of course it's not the most efficient way to do this (copying the message twice), but it's working for our application. However, every once in a while (seldom) my program crashes when calling getLastMsg() (double free). I don't see where the problem could be located (if in my code or the C++ copy constructor of ROS msgs). Any tips and comments are greatly appreciated.

Thanks! Martin

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
3

answered 2012-11-12 04:48:06 -0500

Lorenz gravatar image

Maybe a multi-threading problem because your lock does nothing. It should be

boost::mutex::scoped_lock lock(lastMsgLock);

You need to bind it to a variable, otherwise a temporary object is generated that immediately goes out of scope.

Also, why aren't you just storing the shared pointer instead of copying the complete message? It is guaranteed that it will never change. I would also let the getLastMsg method return a const reference, not a copy of the message. The updated class would look like this:

template <class T_>
class GenericSubscriber {
protected:
    boost::shared_ptr<const T_> lastMsg;
    boost::mutex lastMsgLock;

    // Subscriber
    ros::Subscriber sub;

    void msgCallback(boost::shared_ptr<T_ const> msg) {
        boost::mutex::scoped_lock lock(lastMsgLock);
        lastMsg = msg;
    }

public:
    GenericSubscriber(ros::NodeHandle handle, const std::string& topicName, int queue_size) {
        sub = handle.subscribe(topicName, queue_size, &GenericSubscriber<T_>::msgCallback, this);
    }

    virtual ~GenericSubscriber() {};

    const T_ &getLastMsg() const {
        boost::mutex::scoped_lock lock(lastMsgLock);
        return *lastMsg;
    }
};
edit flag offensive delete link more

Comments

Oh man, I'm so stupid. I actually use a lot of scoped_locks. No idea how I could forget it here and not even see it. Thanks a million.

rado0x54 gravatar image rado0x54  ( 2012-11-12 05:01:38 -0500 )edit

Also thanks for the other suggestions. I'll implement this right now.

rado0x54 gravatar image rado0x54  ( 2012-11-12 05:04:38 -0500 )edit

One more question. Could the const T_& not go out of scope (e.g. a new message overwrite the shared_pointer and it frees the space) while an external thread is trying to access it? Thanks.

rado0x54 gravatar image rado0x54  ( 2012-11-12 05:25:39 -0500 )edit

Right. I missed that. Then you better either return a shared pointer or make a shallow copy of the object.

Lorenz gravatar image Lorenz  ( 2012-11-12 05:27:40 -0500 )edit

Question Tools

Stats

Asked: 2012-11-12 03:39:59 -0500

Seen: 825 times

Last updated: Nov 12 '12