From 3d74e20c294857f912c5857e07f5ba59bd984e4e Mon Sep 17 00:00:00 2001 From: atb033 Date: Sat, 28 Mar 2020 16:51:24 +0100 Subject: [PATCH] Add server_name parameter to BtActionNode A BT port is introduced in case the user wants to change the default action_name of BtActionNode. --- .../include/nav2_behavior_tree/bt_action_node.hpp | 7 ++++++- .../plugins/action/compute_path_to_pose_action.cpp | 6 ------ nav2_behavior_tree/plugins/action/follow_path_action.cpp | 6 ------ 3 files changed, 6 insertions(+), 13 deletions(-) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp index b08ff17334..c6e606bedb 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp @@ -41,6 +41,10 @@ class BtActionNode : public BT::ActionNodeBase goal_ = typename ActionT::Goal(); result_ = typename rclcpp_action::ClientGoalHandle::WrappedResult(); + std::string remapped_action_name; + if (getInput("server_name", remapped_action_name)) { + action_name_ = remapped_action_name; + } createActionClient(action_name_); // Give the derive class a chance to do any initialization @@ -69,6 +73,7 @@ class BtActionNode : public BT::ActionNodeBase static BT::PortsList providedBasicPorts(BT::PortsList addition) { BT::PortsList basic = { + BT::InputPort("server_name", "Action server name"), BT::InputPort("server_timeout") }; basic.insert(addition.begin(), addition.end()); @@ -233,7 +238,7 @@ class BtActionNode : public BT::ActionNodeBase } } - const std::string action_name_; + std::string action_name_; typename std::shared_ptr> action_client_; // All ROS2 actions have a goal and a result diff --git a/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp b/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp index 1071e5d99f..be53df37fe 100644 --- a/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp +++ b/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.cpp @@ -34,11 +34,6 @@ class ComputePathToPoseAction : public BtActionNode(xml_tag_name, action_name, conf) { - std::string remapped_action_name; - if (getInput("server_name", remapped_action_name)) { - action_client_.reset(); - createActionClient(remapped_action_name); - } } void on_tick() override @@ -66,7 +61,6 @@ class ComputePathToPoseAction : public BtActionNode("path", "Path created by ComputePathToPose node"), BT::InputPort("goal", "Destination to plan to"), BT::InputPort("planner_id", ""), - BT::InputPort("server_name", "") }); } diff --git a/nav2_behavior_tree/plugins/action/follow_path_action.cpp b/nav2_behavior_tree/plugins/action/follow_path_action.cpp index d3cbbdafe8..820362912e 100644 --- a/nav2_behavior_tree/plugins/action/follow_path_action.cpp +++ b/nav2_behavior_tree/plugins/action/follow_path_action.cpp @@ -33,11 +33,6 @@ class FollowPathAction : public BtActionNode const BT::NodeConfiguration & conf) : BtActionNode(xml_tag_name, action_name, conf) { - std::string remapped_action_name; - if (getInput("server_name", remapped_action_name)) { - action_client_.reset(); - createActionClient(remapped_action_name); - } config().blackboard->set("path_updated", false); } @@ -67,7 +62,6 @@ class FollowPathAction : public BtActionNode { BT::InputPort("path", "Path to follow"), BT::InputPort("controller_id", ""), - BT::InputPort("server_name", "") }); } };