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 the missing ports and description for the XML nodes #2866

Merged
Merged
Show file tree
Hide file tree
Changes from 2 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 @@ -68,7 +68,7 @@ class ComputePathThroughPosesAction
"Destinations to plan through"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"start", "Start pose of the path if overriding current robot pose"),
BT::InputPort<std::string>("planner_id", ""),
BT::InputPort<std::string>("planner_id", "Mapped name to the planner plugin type to use"),
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
});
}
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class ComputePathToPoseAction : public BtActionNode<nav2_msgs::action::ComputePa
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination to plan to"),
BT::InputPort<geometry_msgs::msg::PoseStamped>(
"start", "Start pose of the path if overriding current robot pose"),
BT::InputPort<std::string>("planner_id", ""),
BT::InputPort<std::string>("planner_id", "Mapped name to the planner plugin type to use"),
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
});
}
};
Expand Down
29 changes: 27 additions & 2 deletions nav2_behavior_tree/nav2_tree_nodes.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@
<input_port name="backup_dist">Distance to backup</input_port>
<input_port name="backup_speed">Speed at which to backup</input_port>
<input_port name="time_allowance">Allowed time for reversing</input_port>
<input_port name="server_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="CancelControl">
Expand All @@ -35,25 +37,32 @@

<Action ID="ClearEntireCostmap">
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="ComputePathToPose">
<input_port name="goal">Destination to plan to</input_port>
<input_port name="start">Start pose of the path if overriding current robot pose</input_port>
<input_port name="planner_id">Mapped name to the planner plugin type to use</input_port>
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
<output_port name="path">Path created by ComputePathToPose node</output_port>
<input_port name="planner_id"/>
</Action>

<Action ID="ComputePathThroughPoses">
<input_port name="goals">Destinations to plan through</input_port>
<input_port name="start">Start pose of the path if overriding current robot pose</input_port>
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
<input_port name="planner_id">Mapped name to the planner plugin type to use</input_port>
<output_port name="path">Path created by ComputePathToPose node</output_port>
<input_port name="planner_id"/>
</Action>

<Action ID="RemovePassedGoals">
<input_port name="input_goals">Input goals to remove if passed</input_port>
<input_port name="radius">Radius tolerance on a goal to consider it passed</input_port>
<input_port name="global_frame">Global frame</input_port>
<input_port name="robot_base_frame">Robot base frame</input_port>
<output_port name="output_goals">Set of goals after removing any passed</output_port>
</Action>

Expand All @@ -71,17 +80,25 @@
<input_port name="controller_id" default="FollowPath"/>
<input_port name="path">Path to follow</input_port>
<input_port name="goal_checker_id" default="GoalChecker">Goal checker</input_port>
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="NavigateToPose">
<input_port name="goal">Goal</input_port>
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="NavigateThroughPoses">
<input_port name="goals">Goals</input_port>
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="ReinitializeGlobalLocalization">
<input_port name="service_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="TruncatePath">
Expand Down Expand Up @@ -111,15 +128,21 @@
<Action ID="Spin">
<input_port name="spin_dist">Spin distance</input_port>
<input_port name="time_allowance">Allowed time for spinning</input_port>
<input_port name="server_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<Action ID="Wait">
<input_port name="wait_duration">Wait time</input_port>
<input_port name="server_name">Service name</input_port>
<input_port name="server_timeout">Server timeout</input_port>
</Action>

<!-- ############################### CONDITION NODES ############################## -->
<Condition ID="GoalReached">
<input_port name="goal">Destination</input_port>
<input_port name="global_frame">Reference frame</input_port>
<input_port name="robot_base_frame">Robot base frame</input_port>
</Condition>

<Condition ID="IsStuck"/>
Expand Down Expand Up @@ -173,6 +196,8 @@

<Decorator ID="DistanceController">
<input_port name="distance">Distance</input_port>
<input_port name="global_frame">Reference frame</input_port>
<input_port name="robot_base_frame">Robot base frame</input_port>
</Decorator>

<Decorator ID="SingleTrigger">
Expand Down