Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add server_name parameter to BtActionNode #1616

Merged
merged 1 commit into from
Mar 29, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,10 @@ class BtActionNode : public BT::ActionNodeBase
goal_ = typename ActionT::Goal();
result_ = typename rclcpp_action::ClientGoalHandle<ActionT>::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
Expand Down Expand Up @@ -69,6 +73,7 @@ class BtActionNode : public BT::ActionNodeBase
static BT::PortsList providedBasicPorts(BT::PortsList addition)
{
BT::PortsList basic = {
BT::InputPort<std::string>("server_name", "Action server name"),
BT::InputPort<std::chrono::milliseconds>("server_timeout")
};
basic.insert(addition.begin(), addition.end());
Expand Down Expand Up @@ -233,7 +238,7 @@ class BtActionNode : public BT::ActionNodeBase
}
}

const std::string action_name_;
std::string action_name_;
typename std::shared_ptr<rclcpp_action::Client<ActionT>> action_client_;

// All ROS2 actions have a goal and a result
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,6 @@ class ComputePathToPoseAction : public BtActionNode<nav2_msgs::action::ComputePa
const BT::NodeConfiguration & conf)
: BtActionNode<nav2_msgs::action::ComputePathToPose>(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
Expand Down Expand Up @@ -66,7 +61,6 @@ class ComputePathToPoseAction : public BtActionNode<nav2_msgs::action::ComputePa
BT::OutputPort<nav_msgs::msg::Path>("path", "Path created by ComputePathToPose node"),
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination to plan to"),
BT::InputPort<std::string>("planner_id", ""),
BT::InputPort<std::string>("server_name", "")
});
}

Expand Down
6 changes: 0 additions & 6 deletions nav2_behavior_tree/plugins/action/follow_path_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,6 @@ class FollowPathAction : public BtActionNode<nav2_msgs::action::FollowPath>
const BT::NodeConfiguration & conf)
: BtActionNode<nav2_msgs::action::FollowPath>(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);
}

Expand Down Expand Up @@ -67,7 +62,6 @@ class FollowPathAction : public BtActionNode<nav2_msgs::action::FollowPath>
{
BT::InputPort<nav_msgs::msg::Path>("path", "Path to follow"),
BT::InputPort<std::string>("controller_id", ""),
BT::InputPort<std::string>("server_name", "")
});
}
};
Expand Down