Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

#1608 revisited: Fix subscription busy wait melodic #1684

Merged
15 changes: 15 additions & 0 deletions clients/roscpp/include/ros/callback_queue.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,21 @@
#ifndef ROSCPP_CALLBACK_QUEUE_H
#define ROSCPP_CALLBACK_QUEUE_H

// check if we might need to include our own backported version boost::condition_variable
// in order to use CLOCK_MONOTONIC for the condition variable
// the include order here is important!
#ifdef BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC
#include <boost/version.hpp>
#if BOOST_VERSION < 106100
// use backported version of boost condition variable, see https://svn.boost.org/trac/boost/ticket/6377
#include "boost_161_condition_variable.h"
dirk-thomas marked this conversation as resolved.
Show resolved Hide resolved
#else // Boost version is 1.61 or greater and has the steady clock fixes
#include <boost/thread/condition_variable.hpp>
#endif
#else // !BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC
#include <boost/thread/condition_variable.hpp>
#endif // BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC

dirk-thomas marked this conversation as resolved.
Show resolved Hide resolved
#include "ros/callback_queue_interface.h"
#include "ros/internal/condition_variable.h"
#include "ros/time.h"
Expand Down
22 changes: 21 additions & 1 deletion clients/roscpp/src/libros/callback_queue.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,10 @@ void CallbackQueue::addCallback(const CallbackInterfacePtr& callback, uint64_t r
callbacks_.push_back(info);
}

condition_.notify_one();
if (callback->ready())
{
condition_.notify_one();
}
}

CallbackQueue::IDInfoPtr CallbackQueue::getIDInfo(uint64_t id)
Expand Down Expand Up @@ -225,6 +228,8 @@ CallbackQueue::CallOneResult CallbackQueue::callOne(ros::WallDuration timeout)
return Disabled;
}

ros::SteadyTime start_time(ros::SteadyTime::now());

if (callbacks_.empty())
{
if (!timeout.isZero())
Expand Down Expand Up @@ -266,6 +271,17 @@ CallbackQueue::CallOneResult CallbackQueue::callOne(ros::WallDuration timeout)

if (!cb_info.callback)
{
// do not spend more than `timeout` seconds in the callback; we already waited for some time when waiting for
// nonempty queue
ros::SteadyTime now(ros::SteadyTime::now());
ros::WallDuration time_spent = now - start_time;
ros::WallDuration time_to_wait = timeout - time_spent;

if (time_to_wait.toNSec() > 0)
{
condition_.wait_for(lock, boost::chrono::nanoseconds(time_to_wait.toNSec()));
}

return TryAgain;
}

Expand Down Expand Up @@ -391,6 +407,10 @@ CallbackQueue::CallOneResult CallbackQueue::callOneCB(TLS* tls)
{
tls->cb_it = tls->callbacks.erase(tls->cb_it);
result = cb->call();
if (result == CallbackInterface::Success)
{
condition_.notify_one();
}
}
}

Expand Down
7 changes: 6 additions & 1 deletion clients/roscpp/src/libros/subscription_queue.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,12 @@ CallbackInterface::CallResult SubscriptionQueue::call()

bool SubscriptionQueue::ready()
{
return true;
if (allow_concurrent_callbacks_)
{
return true;
}
boost::recursive_mutex::scoped_try_lock lock(callback_mutex_, boost::try_to_lock);
return lock.owns_lock();
}

bool SubscriptionQueue::full()
Expand Down
91 changes: 91 additions & 0 deletions test/test_roscpp/test/fake_message.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
/*
* Copyright (c) 2009, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

/* Author: Josh Faust */

/*
* Subscription queue test helper classes
*/
#ifndef TEST_ROSCPP_FAKE_MESSAGE_H
#define TEST_ROSCPP_FAKE_MESSAGE_H

#include "ros/subscription_callback_helper.h"

class FakeMessage
{
public:
virtual const std::string __getDataType() const { return ""; }
virtual const std::string __getMD5Sum() const { return ""; }
virtual const std::string __getMessageDefinition() const { return ""; }
virtual uint32_t serializationLength() const { return 0; }
virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const { (void)seq; return write_ptr; }
virtual uint8_t *deserialize(uint8_t *read_ptr) { return read_ptr; }
};

class FakeSubHelper : public ros::SubscriptionCallbackHelper
{
public:
FakeSubHelper()
: calls_(0)
{}

virtual ros::VoidConstPtr deserialize(const ros::SubscriptionCallbackHelperDeserializeParams&)
{
return boost::make_shared<FakeMessage>();
}

virtual std::string getMD5Sum() { return ""; }
virtual std::string getDataType() { return ""; }

virtual void call(ros::SubscriptionCallbackHelperCallParams& params)
{
(void)params;
{
boost::mutex::scoped_lock lock(mutex_);
++calls_;
}

if (cb_)
{
cb_();
}
}

virtual const std::type_info& getTypeInfo() { return typeid(FakeMessage); }
virtual bool isConst() { return true; }
virtual bool hasHeader() { return false; }

boost::mutex mutex_;
uint32_t calls_;

boost::function<void(void)> cb_;
};
typedef boost::shared_ptr<FakeSubHelper> FakeSubHelperPtr;

#endif // TEST_ROSCPP_FAKE_MESSAGE_H
Loading