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 service_name input port ot is_path_valid #21

Open
wants to merge 1 commit into
base: humble
Choose a base branch
from
Open
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
Add service_name input port ot is_path_valid
  • Loading branch information
emilnovak committed Jul 29, 2024
commit 2abe7df1d678f0130e7b7b098e2d7944c3f755db
Original file line number Diff line number Diff line change
Expand Up @@ -58,12 +58,17 @@ class IsPathValidCondition : public BT::ConditionNode
{
return {
BT::InputPort<nav_msgs::msg::Path>("path", "Path to Check"),
BT::InputPort<std::string>(
"service_name",
"is_path_valid",
"Name of the service to call, defaults to is_path_valid"),
BT::InputPort<std::chrono::milliseconds>("server_timeout")
};
}

private:
rclcpp::Node::SharedPtr node_;
std::string service_name_;
rclcpp::Client<nav2_msgs::srv::IsPathValid>::SharedPtr client_;
// The timeout value while waiting for a responce from the
// is path valid service
Expand Down
1 change: 1 addition & 0 deletions nav2_behavior_tree/nav2_tree_nodes.xml
Original file line number Diff line number Diff line change
Expand Up @@ -258,6 +258,7 @@

<Condition ID="IsPathValid">
<input_port name="path"> Path to validate </input_port>
<input_port name="service_name">Name of the service to call, defaults to is_path_valid</input_port>
<input_port name="server_timeout"> Server timeout </input_port>
</Condition>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,12 @@ IsPathValidCondition::IsPathValidCondition(
: BT::ConditionNode(condition_name, conf)
{
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
client_ = node_->create_client<nav2_msgs::srv::IsPathValid>("is_path_valid");

server_timeout_ = config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);

getInput("service_name", service_name_);
client_ = node_->create_client<nav2_msgs::srv::IsPathValid>(service_name_);
}

BT::NodeStatus IsPathValidCondition::tick()
Expand Down