Skip to content

Commit

Permalink
Address deprecations of StaticSingleThreadedExecutor and realtime_too…
Browse files Browse the repository at this point in the history
…ls/thread_priority.hpp (#3139)

* Switch StaticSingleThreadedExecutor to SingleThreadedExecutor

* Update realtime_tools header in servo node too

* Conditional include

* Update moveit_ros/moveit_servo/src/servo_node.cpp

* Update moveit_ros/moveit_servo/src/servo_node.cpp

---------

Co-authored-by: Michael Ferguson <mfergs7@gmail.com>
  • Loading branch information
sea-bass and mikeferguson authored Nov 29, 2024
1 parent 397843c commit b781196
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 3 deletions.
7 changes: 6 additions & 1 deletion moveit_ros/moveit_servo/src/servo_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,14 @@
*
*/

#include <moveit_servo/servo_node.hpp>
#if __has_include(<realtime_tools/realtime_helpers.hpp>)
#include <realtime_tools/realtime_helpers.hpp>
#else
#include <realtime_tools/thread_priority.hpp>
#endif

#include <moveit/utils/logger.hpp>
#include <moveit_servo/servo_node.hpp>

namespace moveit_servo
{
Expand Down
4 changes: 2 additions & 2 deletions moveit_ros/warehouse/src/broadcast.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <boost/program_options/options_description.hpp>
#include <boost/program_options/parsers.hpp>
#include <boost/program_options/variables_map.hpp>
#include <rclcpp/executors/static_single_threaded_executor.hpp>
#include <rclcpp/executors/single_threaded_executor.hpp>
#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/node.hpp>
Expand Down Expand Up @@ -118,7 +118,7 @@ int main(int argc, char** argv)
if (!conn->connect())
return 1;

rclcpp::executors::StaticSingleThreadedExecutor executor;
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);

rclcpp::Rate rate(static_cast<int64_t>(delay) * 1000ms);
Expand Down

0 comments on commit b781196

Please sign in to comment.