diff --git a/moveit_ros/moveit_servo/CMakeLists.txt b/moveit_ros/moveit_servo/CMakeLists.txt
index c05231b38b5..6f070f6910e 100644
--- a/moveit_ros/moveit_servo/CMakeLists.txt
+++ b/moveit_ros/moveit_servo/CMakeLists.txt
@@ -33,7 +33,6 @@ moveit_package()
set(THIS_PACKAGE_INCLUDE_DEPENDS
control_msgs
control_toolbox
- controller_manager
geometry_msgs
moveit_core
moveit_msgs
@@ -41,6 +40,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
pluginlib
rclcpp
rclcpp_components
+ realtime_tools
sensor_msgs
std_msgs
std_srvs
diff --git a/moveit_ros/moveit_servo/package.xml b/moveit_ros/moveit_servo/package.xml
index 4933f8b43f3..c6a6fb5329e 100644
--- a/moveit_ros/moveit_servo/package.xml
+++ b/moveit_ros/moveit_servo/package.xml
@@ -25,18 +25,19 @@
control_msgs
control_toolbox
- controller_manager
geometry_msgs
moveit_msgs
moveit_core
moveit_ros_planning_interface
pluginlib
+ realtime_tools
sensor_msgs
std_msgs
std_srvs
tf2_eigen
trajectory_msgs
+ controller_manager
gripper_controllers
joint_state_broadcaster
joint_trajectory_controller
@@ -49,7 +50,6 @@
ament_cmake_gtest
ament_lint_auto
ament_lint_common
- controller_manager
moveit_resources_panda_moveit_config
ros_testing
diff --git a/moveit_ros/moveit_servo/src/servo_calcs.cpp b/moveit_ros/moveit_servo/src/servo_calcs.cpp
index 46e414840aa..3e3d92353aa 100644
--- a/moveit_ros/moveit_servo/src/servo_calcs.cpp
+++ b/moveit_ros/moveit_servo/src/servo_calcs.cpp
@@ -42,7 +42,7 @@
#include
#include
-#include
+#include
#include
#include
@@ -277,9 +277,9 @@ void ServoCalcs::start()
stop_requested_ = false;
thread_ = std::thread([this] {
// Check if a realtime kernel is installed. Set a higher thread priority, if so
- if (controller_manager::has_realtime_kernel())
+ if (realtime_tools::has_realtime_kernel())
{
- if (!controller_manager::configure_sched_fifo(THREAD_PRIORITY))
+ if (!realtime_tools::configure_sched_fifo(THREAD_PRIORITY))
{
RCLCPP_WARN(LOGGER, "Could not enable FIFO RT scheduling policy");
}