Skip to content

Commit dc691bf

Browse files
committed
Add action options
1 parent 70e81f5 commit dc691bf

File tree

3 files changed

+16
-10
lines changed

3 files changed

+16
-10
lines changed

behaviortree_ros2/include/behaviortree_ros2/bt_action_node.hpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -174,7 +174,8 @@ class RosActionNode : public BT::ActionNodeBase
174174
struct ActionClientInstance
175175
{
176176
ActionClientInstance(std::shared_ptr<rclcpp::Node> node,
177-
const std::string& action_name);
177+
const std::string& action_name,
178+
const rcl_action_client_options_t& action_client_options);
178179

179180
ActionClientPtr action_client;
180181
rclcpp::CallbackGroup::SharedPtr callback_group;
@@ -222,6 +223,7 @@ class RosActionNode : public BT::ActionNodeBase
222223
const std::chrono::milliseconds server_timeout_;
223224
const std::chrono::milliseconds wait_for_server_timeout_;
224225
std::string action_client_key_;
226+
rcl_action_client_options_t action_client_options_;
225227

226228
private:
227229
std::shared_future<typename GoalHandle::SharedPtr> future_goal_handle_;
@@ -241,12 +243,14 @@ class RosActionNode : public BT::ActionNodeBase
241243

242244
template <class T>
243245
RosActionNode<T>::ActionClientInstance::ActionClientInstance(
244-
std::shared_ptr<rclcpp::Node> node, const std::string& action_name)
246+
std::shared_ptr<rclcpp::Node> node, const std::string& action_name,
247+
const rcl_action_client_options_t& action_client_options)
245248
{
246249
callback_group =
247250
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
248251
callback_executor.add_callback_group(callback_group, node->get_node_base_interface());
249-
action_client = rclcpp_action::create_client<T>(node, action_name, callback_group);
252+
action_client = rclcpp_action::create_client<T>(node, action_name, callback_group,
253+
action_client_options);
250254
}
251255

252256
template <class T>
@@ -257,6 +261,7 @@ inline RosActionNode<T>::RosActionNode(const std::string& instance_name,
257261
, node_(params.nh)
258262
, server_timeout_(params.server_timeout)
259263
, wait_for_server_timeout_(params.wait_for_server_timeout)
264+
, action_client_options_(params.action_client_options)
260265
{
261266
// Three cases:
262267
// - we use the default action_name in RosNodeParams when port is empty
@@ -308,7 +313,8 @@ inline bool RosActionNode<T>::createClient(const std::string& action_name)
308313
auto it = registry.find(action_client_key_);
309314
if(it == registry.end() || it->second.expired())
310315
{
311-
client_instance_ = std::make_shared<ActionClientInstance>(node, action_name);
316+
client_instance_ =
317+
std::make_shared<ActionClientInstance>(node, action_name, action_client_options_);
312318
registry.insert({ action_client_key_, client_instance_ });
313319
}
314320
else

behaviortree_ros2/include/behaviortree_ros2/bt_service_node.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -144,7 +144,7 @@ class RosServiceNode : public BT::ActionNodeBase
144144
{
145145
ServiceClientInstance(std::shared_ptr<rclcpp::Node> node,
146146
const std::string& service_name,
147-
const rmw_qos_profile_t qos_profile);
147+
const rmw_qos_profile_t& qos_profile);
148148

149149
ServiceClientPtr service_client;
150150
rclcpp::CallbackGroup::SharedPtr callback_group;
@@ -213,7 +213,7 @@ class RosServiceNode : public BT::ActionNodeBase
213213
template <class T>
214214
inline RosServiceNode<T>::ServiceClientInstance::ServiceClientInstance(
215215
std::shared_ptr<rclcpp::Node> node, const std::string& service_name,
216-
const rmw_qos_profile_t qos_profile)
216+
const rmw_qos_profile_t& qos_profile)
217217
{
218218
callback_group =
219219
node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false);

behaviortree_ros2/include/behaviortree_ros2/ros_node_params.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -36,12 +36,12 @@ struct RosNodeParams
3636
// - RosTopicSubNode: name of the topic to subscribe to
3737
std::string default_port_value;
3838

39-
// Different configuration based on the context:
40-
rclcpp::QoS topic_qos =
41-
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default));
42-
rmw_qos_profile_t service_qos_profile = rmw_qos_profile_services_default;
39+
// Default qos configuration for actions, services and topics
4340
rcl_action_client_options_t action_client_options =
4441
rcl_action_client_get_default_options();
42+
rmw_qos_profile_t service_qos_profile = rmw_qos_profile_services_default;
43+
rclcpp::QoS topic_qos =
44+
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default));
4545

4646
// parameters used only by service client and action clients
4747

0 commit comments

Comments
 (0)