Skip to content

Commit

Permalink
Fix services QoS
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored Jan 16, 2025
1 parent 06829ee commit 217a6d8
Showing 1 changed file with 29 additions and 5 deletions.
34 changes: 29 additions & 5 deletions io_gripper_controller/src/io_gripper_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,32 @@
#include <vector>

#include "controller_interface/helpers.hpp"

#include "rclcpp/version.h"

namespace
{ // utility

// Changed services history QoS to keep all so we don't lose any client service calls
// \note The versions conditioning is added here to support the source-compatibility with Humble
#if RCLCPP_VERSION_MAJOR >= 17
rclcpp::QoS qos_services =
rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1))
.reliable()
.durability_volatile();
#else
static const rmw_qos_profile_t qos_services = {
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};
#endif

} // namespace

namespace io_gripper_controller
{
Expand Down Expand Up @@ -866,8 +891,7 @@ controller_interface::CallbackReturn IOGripperController::prepare_publishers_and
};

open_service_ = get_node()->create_service<OpenCloseSrvType>(
"~/gripper_open", open_service_callback, rmw_qos_profile_services_hist_keep_all,
open_service_callback_group_);
"~/gripper_open", open_service_callback, qos_services, open_service_callback_group_);

// close service
auto close_service_callback = [&](
Expand Down Expand Up @@ -940,8 +964,8 @@ controller_interface::CallbackReturn IOGripperController::prepare_publishers_and
};

configure_gripper_service_ = get_node()->create_service<ConfigSrvType>(
"~/reconfigure_to", configure_gripper_service_callback,
rmw_qos_profile_services_hist_keep_all, reconfigure_service_callback_group_);
"~/reconfigure_to", configure_gripper_service_callback, qos_services,
reconfigure_service_callback_group_);
}
else
{
Expand Down

0 comments on commit 217a6d8

Please sign in to comment.