Skip to content

Commit

Permalink
server node: use MultiThreadedSpinner
Browse files Browse the repository at this point in the history
Add a new optional parameter, thread_count, to use as the number of
threads to pass to the new MultiThreadedSpinner. The thread_count
defaults to 0, which means one thread per core. A negative thread_count
means to go back to the old single-threaded spin(). A positive
thread_count means to spin a multi-threaded spinner with that number of
threads.
  • Loading branch information
c-andy-martin committed Feb 29, 2024
1 parent 75aaf27 commit eff7084
Showing 1 changed file with 12 additions and 1 deletion.
13 changes: 12 additions & 1 deletion mbf_costmap_nav/src/move_base_server_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,8 @@ int main(int argc, char **argv)
private_nh.param("tf_cache_time", cache_time, 10.0);
bool use_costmap_3d;
private_nh.param("use_costmap_3d", use_costmap_3d, false);
int thread_count;
private_nh.param("thread_count", thread_count, 0);

signal(SIGINT, sigintHandler);
#ifdef USE_OLD_TF
Expand All @@ -82,7 +84,16 @@ int main(int argc, char **argv)
costmap_nav_srv_ptr = boost::make_shared<
mbf_costmap_nav::CostmapNavigationServer<costmap_2d::Costmap2DROS>>(tf_listener_ptr);
}
ros::spin();
// Negative thread count, means just use a single thread
if (thread_count < 0)
{
ros::spin();
}
else
{
ros::MultiThreadedSpinner spinner(thread_count);
spinner.spin();
}

if (costmap_nav_srv_ptr)
{
Expand Down

0 comments on commit eff7084

Please sign in to comment.