Skip to content
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 @@ -65,7 +65,7 @@ BTs are primarily defined in XML. The tree shown above is represented in XML as
</Inverter>
<IsGoalNearby path="{path}" proximity_threshold="4.0" max_robot_pose_search_dist="1.5"/>
<TruncatePathLocal input_path="{path}" output_path="{remaining_path}" distance_forward="-1" distance_backward="0.0" />
<IsPathValid path="{remaining_path}"/>
<ValidatePath path="{remaining_path}"/>
</ReactiveSequence>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
</Fallback>
Expand Down Expand Up @@ -172,7 +172,7 @@ The XML of this subtree is as follows:
</Inverter>
<IsGoalNearby path="{path}" proximity_threshold="4.0" max_robot_pose_search_dist="1.5"/>
<TruncatePathLocal input_path="{path}" output_path="{remaining_path}" distance_forward="-1" distance_backward="0.0" />
<IsPathValid path="{remaining_path}"/>
<ValidatePath path="{remaining_path}"/>
</ReactiveSequence>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
</Fallback>
Expand Down
2 changes: 1 addition & 1 deletion behavior_trees/trees/nav_through_poses_recovery.rst
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
</Inverter>
<IsGoalNearby path="{path}" proximity_threshold="4.0" max_robot_pose_search_dist="1.5"/>
<TruncatePathLocal input_path="{path}" output_path="{remaining_path}" distance_forward="-1" distance_backward="0.0" />
<IsPathValid path="{remaining_path}"/>
<ValidatePath path="{remaining_path}"/>
</ReactiveSequence>
<ReactiveSequence>
<RemovePassedGoals input_goals="{goals}" output_goals="{goals}" radius="0.7" input_waypoint_statuses="{waypoint_statuses}" output_waypoint_statuses="{waypoint_statuses}"/>
Expand Down
2 changes: 1 addition & 1 deletion behavior_trees/trees/nav_to_pose_recovery.rst
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
</Inverter>
<IsGoalNearby path="{path}" proximity_threshold="4.0" max_robot_pose_search_dist="1.5"/>
<TruncatePathLocal input_path="{path}" output_path="{remaining_path}" distance_forward="-1" distance_backward="0.0" />
<IsPathValid path="{remaining_path}"/>
<ValidatePath path="{remaining_path}"/>
</ReactiveSequence>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
</Fallback>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
</Inverter>
<IsGoalNearby path="{path}" proximity_threshold="4.0" max_robot_pose_search_dist="1.5"/>
<TruncatePathLocal input_path="{path}" output_path="{remaining_path}" distance_forward="-1" distance_backward="0.0" />
<IsPathValid path="{remaining_path}"/>
<ValidatePath path="{remaining_path}"/>
</ReactiveSequence>
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
</Fallback>
Expand Down
4 changes: 2 additions & 2 deletions behavior_trees/trees/navigate_on_route_graph_w_recovery.rst
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ This behavior tree implements a different style of navigation than the other ver
Rather than using a freespace planner ``ComputePathToPose`` to plan a complete path to the goal, this behavior tree instead uses the Route Server to find a route to the goal through a pre-defined navigation graph.
This can be useful for navigating in large-scale environments where real-time planning in freespace for a long distance is not computationally feasible, where a map of the entire space is not possible to plan within, or where deterministic behavior and limited navigation zones/lanes/routes are demanded.

This tree computes a route through the environment using the ``ComputeRoute`` node which is executed on initialization and when either the goal is updated due to preemption (``GlobalUpdatedGoal``) or the current route path is invalid due to collision (``isPathValid``).
This tree computes a route through the environment using the ``ComputeRoute`` node which is executed on initialization and when either the goal is updated due to preemption (``GlobalUpdatedGoal``) or the current route path is invalid due to collision (``ValidatePath``).
After which, if the robot's starting pose is too far from the first route node in the graph solution, it will use freespace planning to connect the robot's current pose to the first node in the route.
This is called the ``first mile`` and is computed using the ``ComputePathToPose`` node.
This may be removed if navigation only on the graph is required and you know that the robot will always be located on or near the graph.
Expand Down Expand Up @@ -35,7 +35,7 @@ For a detailed description of the role of the selector nodes, recovery behaviors
<Inverter>
<GlobalUpdatedGoal/>
</Inverter>
<IsPathValid path="{path}"/> <!-- Base it on the complete connected 'path', not simply the 'route_path' -->
<ValidatePath path="{path}"/> <!-- Base it on the complete connected 'path', not simply the 'route_path' -->
</ReactiveSequence>
<Sequence name="ComputeAndSmoothRoute">
<!-- Compute the route -->
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
.. _bt_is_pose_occupied_condition:
.. _bt_check_pose_occupancy_action:

IsPoseOccupied
==============
CheckPoseOccupancy
==================

Checks to see if the pose is occupied. If it is occupied, the condition returns SUCCESS, otherwise
Checks to see if the pose is occupied. If it is occupied, it returns SUCCESS, otherwise
it returns FAILURE.

Input Ports
Expand Down Expand Up @@ -81,4 +81,4 @@ Example

.. code-block:: xml

<IsPoseOccupied server_timeout="10" pose="{goal}"/>
<CheckPoseOccupancy server_timeout="10" pose="{goal}"/>
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
.. _bt_is_stopped_condition:
.. _bt_check_stop_status_action:

IsStopped
=========
CheckStopStatus
===============

BT node that tracks robot odometry and returns SUCCESS if robot is considered stopped for long enough,
RUNNING if stopped but not for long enough and FAILURE otherwise
Expand Down Expand Up @@ -36,4 +36,4 @@ Example

.. code-block:: xml

<IsStopped velocity_threshold="0.01" duration_stopped="1000"/>
<CheckStopStatus velocity_threshold="0.01" duration_stopped="1000"/>
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
.. _bt_is_path_valid_condition:
.. _bt_validate_path_action:

IsPathValid
===========
ValidatePath
============

Checks to see if the global path is valid. If there is an
obstacle along the path, the condition returns FAILURE, otherwise
obstacle along the path, it returns FAILURE, otherwise
it returns SUCCESS. Optionally checks specific costmap layers and
can use a custom footprint for validation.

Expand Down Expand Up @@ -114,7 +114,7 @@ Example

.. code-block:: xml

<IsPathValid
<ValidatePath
server_timeout="10"
path="{path}"
max_cost="100"
Expand All @@ -128,7 +128,7 @@ With custom footprint:

.. code-block:: xml

<IsPathValid
<ValidatePath
path="{path}"
footprint="[[0.5,0.5],[0.5,-0.5],[-0.5,-0.5],[-0.5,0.5]]"
collision_poses="{collision_poses}" />
Expand All @@ -137,7 +137,7 @@ Checking a specific costmap layer:

.. code-block:: xml

<IsPathValid
<ValidatePath
path="{path}"
layer_name="obstacle_layer"
check_full_path="true"
Expand Down
6 changes: 3 additions & 3 deletions configuration/packages/configuring-bt-xml.rst
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ Action Plugins
bt-plugins/actions/ToggleCollisionMonitor.rst
bt-plugins/actions/FollowObject.rst
bt-plugins/actions/CancelFollowObject.rst
bt-plugins/actions/ValidatePath.rst
bt-plugins/actions/CheckPoseOccupancy.rst
bt-plugins/actions/CheckStopStatus.rst

Condition Plugins
*****************
Expand All @@ -82,11 +85,8 @@ Condition Plugins
bt-plugins/conditions/InitialPoseReceived.rst
bt-plugins/conditions/IsGoalNearby.rst
bt-plugins/conditions/IsStuck.rst
bt-plugins/conditions/IsStopped.rst
bt-plugins/conditions/TimeExpired.rst
bt-plugins/conditions/IsBatteryLow.rst
bt-plugins/conditions/IsPathValid.rst
bt-plugins/conditions/IsPoseOccupied.rst
bt-plugins/conditions/IsWithinPathTrackingBounds.rst
bt-plugins/conditions/PathExpiringTimer.rst
bt-plugins/conditions/AreErrorCodesPresent.rst
Expand Down
11 changes: 11 additions & 0 deletions migration/Kilted.rst
Original file line number Diff line number Diff line change
Expand Up @@ -833,3 +833,14 @@ Refactored Inflation layer powered by OpenMP

The new implementation replaces the previous queue-based cell iteration with a Felzenszwalb-Huttenlocher distance transform algorithm.
When OpenMP is not available at compile time, the layer falls back to single-threaded operation.

Move isStopped, isPathValid, and isPoseOccupied from condition nodes to action nodes
------------------------------------------------------------------------------------

In `PR 5991 <https://github.com/ros-navigation/navigation2/pull/5991>`_, the following nodes were moved from condition nodes to action nodes and renamed:

- `IsStopped` is now `CheckStopStatus`
- `IsPathValid` is now `ValidatePath`
- `IsPoseOccupied` is now `CheckPoseOccupancy`

This change was made because these behavior tree nodes may return RUNNING or require more time to complete, making them unsuitable for behavior tree that are expected to be ticked at 100 Hz.
29 changes: 13 additions & 16 deletions plugins/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -489,6 +489,16 @@ Behavior Tree Nodes
+---------------------------------------------+---------------------+------------------------------------------+
| `Cancel Follow Object`_ | Alberto Tudela | Cancels follow object action |
+---------------------------------------------+---------------------+------------------------------------------+
| `Validate Path`_ | Joshua Wallace | Checks if a path is valid by making |
| | | sure there are no LETHAL obstacles along |
| | | the path. |
+---------------------------------------------+---------------------+------------------------------------------+
| `Check Stop Status`_ | Tony Najjar | Checks if robot is |
| | | stopped for a duration |
+---------------------------------------------+---------------------+------------------------------------------+
| `Check Pose Occupancy`_ | Maurice Alexander | Checks if a pose is occupied. |
| | Purnawan | |
+---------------------------------------------+---------------------+------------------------------------------+

.. _Back Up Action: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/action/back_up_action.cpp
.. _Drive On Heading Action: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp
Expand Down Expand Up @@ -537,7 +547,9 @@ Behavior Tree Nodes
.. _Toggle Collision Monitor Service: https://github.com/ros-navigation/navigation2/blob/main/nav2_behavior_tree/plugins/action/toggle_collision_monitor_service.cpp
.. _Follow Object: https://github.com/ros-navigation/navigation2/blob/main/nav2_behavior_tree/plugins/action/follow_object_action.cpp
.. _Cancel Follow Object: https://github.com/ros-navigation/navigation2/blob/main/nav2_behavior_tree/plugins/action/follow_object_cancel_node.cpp

.. _Validate Path: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/action/validate_path_action.cpp
.. _Check Stop Status: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/action/check_stop_status_action.cpp
.. _Check Pose Occupancy: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/action/check_pose_occupancy_action.cpp

+------------------------------------+--------------------+------------------------+
| Condition Plugin Name | Creator | Description |
Expand All @@ -559,9 +571,6 @@ Behavior Tree Nodes
| | | making progress or |
| | | stuck |
+------------------------------------+--------------------+------------------------+
| `Is Stopped Condition`_ | Tony Najjar | Checks if robot is |
| | | stopped for a duration |
+------------------------------------+--------------------+------------------------+
| `Transform Available Condition`_ | Steve Macenski | Checks if a TF |
| | | transformation is |
| | | available. When |
Expand All @@ -581,12 +590,6 @@ Behavior Tree Nodes
| | | percentage is below |
| | | a specified value. |
+------------------------------------+--------------------+------------------------+
| `Is Path Valid Condition`_ | Joshua Wallace | Checks if a path is |
| | | valid by making sure |
| | | there are no LETHAL |
| | | obstacles along the |
| | | path. |
+------------------------------------+--------------------+------------------------+
| `Path Expiring Timer`_ | Joshua Wallace | Checks if the timer has|
| | | expired. The timer is |
| | | reset if the path gets |
Expand Down Expand Up @@ -622,9 +625,6 @@ Behavior Tree Nodes
| `Are Poses Near Condition`_ | Steve Macenski | Checks if 2 poses are |
| | | nearby to each other. |
+------------------------------------+--------------------+------------------------+
| `Is Pose Occupied Condition`_ | Maurice Alexander | Checks if a pose is |
| | Purnawan | occupied. |
+------------------------------------+--------------------+------------------------+
| `Is Goal Nearby Condition`_ | Jakub Chudziński | Checks if the robot is |
| | | near the goal based on |
| | | remaining path length. |
Expand All @@ -639,12 +639,10 @@ Behavior Tree Nodes
.. _Global Updated Goal Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp
.. _Initial Pose received Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/initial_pose_received_condition.cpp
.. _Is Stuck Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp
.. _Is Stopped Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/is_stopped_condition.cpp
.. _Transform Available Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp
.. _Distance Traveled Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/distance_traveled_condition.cpp
.. _Time Expired Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/time_expired_condition.cpp
.. _Is Battery Low Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp
.. _Is Path Valid Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/is_path_valid_condition.cpp
.. _Path Expiring Timer: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.cpp
.. _Are Error Codes Present: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.cpp
.. _Would A Controller Recovery Help: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.cpp
Expand All @@ -653,7 +651,6 @@ Behavior Tree Nodes
.. _Would A Route Recovery Help: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/would_a_route_recovery_help_condition.cpp
.. _Is Battery Charging Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp
.. _Are Poses Near Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/are_poses_near_condition.cpp
.. _Is Pose Occupied Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/is_pose_occupied_condition.cpp
.. _Is Goal Nearby Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/is_goal_nearby_condition.cpp
.. _Is Within Path Tracking Bounds Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/is_within_path_tracking_bounds_condition.cpp

Expand Down
Loading