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

changed error message for single threaded spinner #1164

Merged
Merged
Changes from 2 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
13 changes: 7 additions & 6 deletions clients/roscpp/src/libros/spinner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,7 @@ struct SpinnerMonitor

SpinnerMonitor spinner_monitor;
const std::string DEFAULT_ERROR_MESSAGE =
"Attempt to spin a callback queue from two spinners, one of them being single-threaded. "
"This will probably result in callbacks being executed out-of-order.";
"Attempt to spin a callback queue from two spinners, one of them being single-threaded. ";
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please remove the trailing space between the dot and the closing quote.

}

namespace ros
Expand All @@ -130,8 +129,9 @@ void SingleThreadedSpinner::spin(CallbackQueue* queue)

if (!spinner_monitor.add(queue, true))
{
ROS_FATAL_STREAM("SingleThreadedSpinner: " << DEFAULT_ERROR_MESSAGE);
throw std::runtime_error("There is already another spinner on this queue");
std::string errorMessage = "SingleThreadedSpinner: " + DEFAULT_ERROR_MESSAGE + "You might want to use a MultiThreadedSpinner instead.";
ROS_FATAL_STREAM(errorMessage);
throw std::runtime_error(errorMessage);
}

ros::WallDuration timeout(0.1f);
Expand Down Expand Up @@ -220,8 +220,9 @@ void AsyncSpinnerImpl::start()

if (!spinner_monitor.add(callback_queue_, false))
{
ROS_FATAL_STREAM("AsyncSpinnerImpl: " << DEFAULT_ERROR_MESSAGE);
throw std::runtime_error("There is already a single-threaded spinner on this queue");
std::string errorMessage = "AsyncSpinnerImpl: " + DEFAULT_ERROR_MESSAGE;
ROS_FATAL_STREAM(errorMessage);
throw std::runtime_error(errorMessage);
}

continue_ = true;
Expand Down