From 570bbb8aa9798baf644009fb69f50829eb99478f Mon Sep 17 00:00:00 2001 From: Andy McEvoy Date: Fri, 6 Jan 2023 06:41:45 -0600 Subject: [PATCH] Fix QoS deprecation warnings (#879) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Bence Magyar Co-authored-by: Denis Štogl --- controller_manager/src/controller_manager.cpp | 46 ++++++++----------- 1 file changed, 20 insertions(+), 26 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 1e226b97ad..8ce3be22a6 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -36,16 +36,10 @@ static constexpr const char * kChainableControllerInterfaceClassName = "controller_interface::ChainableControllerInterface"; // Changed services history QoS to keep all so we don't lose any client service calls -static const rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all = { - RMW_QOS_POLICY_HISTORY_KEEP_ALL, - 1, // message queue depth - RMW_QOS_POLICY_RELIABILITY_RELIABLE, - RMW_QOS_POLICY_DURABILITY_VOLATILE, - RMW_QOS_DEADLINE_DEFAULT, - RMW_QOS_LIFESPAN_DEFAULT, - RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT, - RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT, - false}; +rclcpp::QoS qos_services = + rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1)) + .reliable() + .durability_volatile(); inline bool is_controller_inactive(const controller_interface::ControllerInterfaceBase & controller) { @@ -234,47 +228,47 @@ void ControllerManager::init_services() using namespace std::placeholders; list_controllers_service_ = create_service( "~/list_controllers", std::bind(&ControllerManager::list_controllers_srv_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + qos_services, best_effort_callback_group_); list_controller_types_service_ = create_service( "~/list_controller_types", - std::bind(&ControllerManager::list_controller_types_srv_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + std::bind(&ControllerManager::list_controller_types_srv_cb, this, _1, _2), qos_services, + best_effort_callback_group_); load_controller_service_ = create_service( "~/load_controller", std::bind(&ControllerManager::load_controller_service_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + qos_services, best_effort_callback_group_); configure_controller_service_ = create_service( "~/configure_controller", - std::bind(&ControllerManager::configure_controller_service_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + std::bind(&ControllerManager::configure_controller_service_cb, this, _1, _2), qos_services, + best_effort_callback_group_); reload_controller_libraries_service_ = create_service( "~/reload_controller_libraries", std::bind(&ControllerManager::reload_controller_libraries_service_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + qos_services, best_effort_callback_group_); switch_controller_service_ = create_service( "~/switch_controller", - std::bind(&ControllerManager::switch_controller_service_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + std::bind(&ControllerManager::switch_controller_service_cb, this, _1, _2), qos_services, + best_effort_callback_group_); unload_controller_service_ = create_service( "~/unload_controller", - std::bind(&ControllerManager::unload_controller_service_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + std::bind(&ControllerManager::unload_controller_service_cb, this, _1, _2), qos_services, + best_effort_callback_group_); list_hardware_components_service_ = create_service( "~/list_hardware_components", - std::bind(&ControllerManager::list_hardware_components_srv_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + std::bind(&ControllerManager::list_hardware_components_srv_cb, this, _1, _2), qos_services, + best_effort_callback_group_); list_hardware_interfaces_service_ = create_service( "~/list_hardware_interfaces", - std::bind(&ControllerManager::list_hardware_interfaces_srv_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + std::bind(&ControllerManager::list_hardware_interfaces_srv_cb, this, _1, _2), qos_services, + best_effort_callback_group_); set_hardware_component_state_service_ = create_service( "~/set_hardware_component_state", std::bind(&ControllerManager::set_hardware_component_state_srv_cb, this, _1, _2), - rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_); + qos_services, best_effort_callback_group_); } controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_controller(