diff --git a/ur_controllers/include/ur_controllers/ur_configuration_controller.hpp b/ur_controllers/include/ur_controllers/ur_configuration_controller.hpp index 3775ee72..30a7378a 100644 --- a/ur_controllers/include/ur_controllers/ur_configuration_controller.hpp +++ b/ur_controllers/include/ur_controllers/ur_configuration_controller.hpp @@ -41,13 +41,10 @@ #ifndef UR_CONTROLLERS__UR_CONFIGURATION_CONTROLLER_HPP_ #define UR_CONTROLLERS__UR_CONFIGURATION_CONTROLLER_HPP_ -// TODO(fmauch): Currently, the realtime_box_best_effort doesn't include this -#include -#include // NOLINT - #include #include +#include #include "ur_msgs/srv/get_robot_software_version.hpp" #include "ur_configuration_controller_parameters.hpp" @@ -88,7 +85,7 @@ class URConfigurationController : public controller_interface::ControllerInterfa CallbackReturn on_init() override; private: - realtime_tools::RealtimeBoxBestEffort> robot_software_version_{ + realtime_tools::RealtimeBox> robot_software_version_{ std::make_shared() };