Skip to content

Commit

Permalink
fix ServicesQoS error (ros-navigation#3449)
Browse files Browse the repository at this point in the history
  • Loading branch information
ObeidHaidar authored and RBT22 committed Oct 24, 2023
1 parent e2bf56c commit 23be4f2
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class BtServiceNode : public BT::ActionNodeBase
getInput("service_name", service_name_);
service_client_ = node_->create_client<ServiceT>(
service_name_,
rclcpp::ServicesQoS(),
rclcpp::ServicesQoS().get_rmw_qos_profile(),
callback_group_);

// Make a request for the service without parameter
Expand Down
4 changes: 2 additions & 2 deletions nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,13 +62,13 @@ LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
manager_srv_ = create_service<ManageLifecycleNodes>(
get_name() + std::string("/manage_nodes"),
std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3),
rclcpp::ServicesQoS(),
rclcpp::ServicesQoS().get_rmw_qos_profile(),
callback_group_);

is_active_srv_ = create_service<std_srvs::srv::Trigger>(
get_name() + std::string("/is_active"),
std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3),
rclcpp::ServicesQoS(),
rclcpp::ServicesQoS().get_rmw_qos_profile(),
callback_group_);

transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE;
Expand Down
2 changes: 1 addition & 1 deletion nav2_util/include/nav2_util/service_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class ServiceClient
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
client_ = node_->create_client<ServiceT>(
service_name,
rclcpp::ServicesQoS(),
rclcpp::ServicesQoS().get_rmw_qos_profile(),
callback_group_);
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_waypoint_follower/plugins/photo_at_waypoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include "pluginlib/class_list_macros.hpp"

#include "nav2_util/node_utils.hpp"
#include "nav2_util/node_utils.h"

namespace nav2_waypoint_follower
{
Expand Down

0 comments on commit 23be4f2

Please sign in to comment.