Skip to content

Commit

Permalink
Smaller shim
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw committed Oct 18, 2022
1 parent f112b02 commit 5acb2f9
Showing 1 changed file with 16 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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 ServiceT>
typename rclcpp::Client<ServiceT>::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<ServiceT>(name, rclcpp::SystemDefaultsQoS(), group);
auto qos_default()
{
return rclcpp::SystemDefaultsQoS();
}
#else
// Humble
return node->create_client<ServiceT>(name, rmw_qos_profile_services_default, group);
#endif
auto qos_default()
{
return rmw_qos_profile_services_default;
}
#endif

} // namespace

Expand Down Expand Up @@ -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<std::chrono::duration<double>>());

query_service_ = create_client_default_qos<moveit_msgs::srv::QueryPlannerInterfaces>(
node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::QUERY_PLANNERS_SERVICE_NAME),
query_service_ = node_->create_client<moveit_msgs::srv::QueryPlannerInterfaces>(
rclcpp::names::append(opt_.move_group_namespace_, move_group::QUERY_PLANNERS_SERVICE_NAME), qos_default(),
callback_group_);
get_params_service_ = create_client_default_qos<moveit_msgs::srv::GetPlannerParams>(
node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::GET_PLANNER_PARAMS_SERVICE_NAME),
get_params_service_ = node_->create_client<moveit_msgs::srv::GetPlannerParams>(
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<moveit_msgs::srv::SetPlannerParams>(
node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::SET_PLANNER_PARAMS_SERVICE_NAME),
set_params_service_ = node_->create_client<moveit_msgs::srv::SetPlannerParams>(
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<moveit_msgs::srv::GetCartesianPath>(
node_, rclcpp::names::append(opt_.move_group_namespace_, move_group::CARTESIAN_PATH_SERVICE_NAME),
cartesian_path_service_ = node_->create_client<moveit_msgs::srv::GetCartesianPath>(
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_ << ".");
Expand Down

0 comments on commit 5acb2f9

Please sign in to comment.