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

roscpp: Adding AsyncSpinner::canStart to check if a spinner can be started #377

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions clients/roscpp/include/ros/spinner.h
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,11 @@ class ROSCPP_DECL AsyncSpinner



/**
* \brief Check if the spinner can be started. A spinner can't be started if
* another spinner is already running.
*/
bool canStart();
/**
* \brief Start this spinner spinning asynchronously
*/
Expand Down
21 changes: 19 additions & 2 deletions clients/roscpp/src/libros/spinner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,8 @@ class AsyncSpinnerImpl
public:
AsyncSpinnerImpl(uint32_t thread_count, CallbackQueue* queue);
~AsyncSpinnerImpl();

bool canStart();
void start();
void stop();

Expand Down Expand Up @@ -132,6 +134,13 @@ AsyncSpinnerImpl::~AsyncSpinnerImpl()
stop();
}

bool AsyncSpinnerImpl::canStart()
{
boost::recursive_mutex::scoped_try_lock spinlock(spinmutex);
return spinlock.owns_lock();
}


void AsyncSpinnerImpl::start()
{
boost::mutex::scoped_lock lock(mutex_);
Expand All @@ -141,8 +150,11 @@ void AsyncSpinnerImpl::start()

boost::recursive_mutex::scoped_try_lock spinlock(spinmutex);
if (!spinlock.owns_lock()) {
ROS_ERROR("AsyncSpinnerImpl: Attempt to call spin from multiple "
"threads. We already spin multithreaded.");
ROS_WARN("AsyncSpinnerImpl: Attempt to start() an AsyncSpinner failed "
"because another AsyncSpinner is already running. Note that the "
"other AsyncSpinner might not be using the same callback queue "
"as this AsyncSpinner, in which case no callbacks in your "
"callback queue will be serviced.");
return;
}
spinlock.swap(member_spinlock);
Expand Down Expand Up @@ -202,6 +214,11 @@ AsyncSpinner::AsyncSpinner(uint32_t thread_count, CallbackQueue* queue)
{
}

bool AsyncSpinner::canStart()
{
return impl_->canStart();
}

void AsyncSpinner::start()
{
impl_->start();
Expand Down