From 5acb2f92c5e8f83bd9bbf7774d76ef693d437840 Mon Sep 17 00:00:00 2001 From: Tyler Weaver Date: Tue, 18 Oct 2022 16:17:48 -0600 Subject: [PATCH] Smaller shim --- .../src/move_group_interface.cpp | 34 +++++++++---------- 1 file changed, 16 insertions(+), 18 deletions(-) diff --git a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp index d7e6cea0a68..1624ac3ce52 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp @@ -90,19 +90,17 @@ enum ActiveTargetType // Function to support both Rolling and Humble on the main branch // Rolling has deprecated the version of the create_client method that takes // rmw_qos_profile_services_default for the QoS argument -template -typename rclcpp::Client::SharedPtr create_client_default_qos(const rclcpp::Node::SharedPtr& node, - const std::string& name, - rclcpp::CallbackGroup::SharedPtr group) -{ #if RCLCPP_VERSION_GTE(17, 0, 0) - // Rolling - return node->create_client(name, rclcpp::SystemDefaultsQoS(), group); +auto qos_default() +{ + return rclcpp::SystemDefaultsQoS(); +} #else - // Humble - return node->create_client(name, rmw_qos_profile_services_default, group); -#endif +auto qos_default() +{ + return rmw_qos_profile_services_default; } +#endif } // namespace @@ -181,17 +179,17 @@ class MoveGroupInterface::MoveGroupInterfaceImpl node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::EXECUTE_ACTION_NAME), callback_group_); execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono>()); - query_service_ = create_client_default_qos( - node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::QUERY_PLANNERS_SERVICE_NAME), + query_service_ = node_->create_client( + rclcpp::names::append(opt_.move_group_namespace_, move_group::QUERY_PLANNERS_SERVICE_NAME), qos_default(), callback_group_); - get_params_service_ = create_client_default_qos( - node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::GET_PLANNER_PARAMS_SERVICE_NAME), + get_params_service_ = node_->create_client( + rclcpp::names::append(opt_.move_group_namespace_, move_group::GET_PLANNER_PARAMS_SERVICE_NAME), qos_default(), callback_group_); - set_params_service_ = create_client_default_qos( - node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::SET_PLANNER_PARAMS_SERVICE_NAME), + set_params_service_ = node_->create_client( + rclcpp::names::append(opt_.move_group_namespace_, move_group::SET_PLANNER_PARAMS_SERVICE_NAME), qos_default(), callback_group_); - cartesian_path_service_ = create_client_default_qos( - node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::CARTESIAN_PATH_SERVICE_NAME), + cartesian_path_service_ = node_->create_client( + rclcpp::names::append(opt_.move_group_namespace_, move_group::CARTESIAN_PATH_SERVICE_NAME), qos_default(), callback_group_); RCLCPP_INFO_STREAM(LOGGER, "Ready to take commands for planning group " << opt.group_name_ << ".");