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
4 changes: 2 additions & 2 deletions behavior_trees/overview/nav2_specific_nodes.rst
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
.. _nav2_specifc_nodes:
.. _nav2_specific_nodes:

Introduction To Nav2 Specific Nodes
===================================
Expand Down Expand Up @@ -33,7 +33,7 @@ Condition Nodes

* GoalReached - Checks if the goal has been reached

* InitialPoseReceived - Checks to see if a pose on the ``intial_pose`` topic has been received
* InitialPoseReceived - Checks to see if a pose on the ``initial_pose`` topic has been received

* isBatteryLow - Checks to see if the battery is low by listening on the battery topic

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ If there is no significantly longer path, the monitor node goes into the ``Follo
.. image:: ../images/walkthrough/patience_and_recovery.png

Once there is a significantly longer path, the child node for the ``PathLongerOnApproach`` node ticks.
The child node is a ``RetryUntilSuccesful`` decorator node, which inturns have a ``SequenceWithMemory`` node as its child.
The child node is a ``RetryUntilSuccessful`` decorator node, which inturns have a ``SequenceWithMemory`` node as its child.
Firstly, the ``SequenceWithMemory`` node cancels the controller server by ticking the ``CancelControl`` node. The cancellation of the controller server halts the further navigation of the robot.
Next, the ``SequenceWithMemory`` node ticks the ``Wait`` node, which enables the robot to wait for the given user-specified time.
Here we need to note that, the ``MonitorAndFollowPath`` is a ``ReactiveSequence`` node, therefore the ``PathLongerOnApproach`` node needs to return SUCCESS, before the ``FollowPath`` node can be ticked once again.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
ProgressCheckerSelector
=======================

It is used to select the ProgressChecker that will be used by the progress_checker server. It subscribes to the ``progress_checker_selector`` topic to receive command messages with the name of the ProgressChecker to be used. It is commonly used before of the FollowPathAction. The ``selected_progess_checker`` output port is passed to ``progress_checker_id`` input port of the FollowPathAction. If none is provided on the topic, the ``default_progress_checker`` is used.
It is used to select the ProgressChecker that will be used by the progress_checker server. It subscribes to the ``progress_checker_selector`` topic to receive command messages with the name of the ProgressChecker to be used. It is commonly used before of the FollowPathAction. The ``selected_progress_checker`` output port is passed to ``progress_checker_id`` input port of the FollowPathAction. If none is provided on the topic, the ``default_progress_checker`` is used.

Any publisher to this topic needs to be configured with some QoS defined as ``reliable`` and ``transient local``.

Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
.. _bt_globally_updated_goal_condition:
.. _bt_global_updated_goal_condition:

GloballyUpdatedGoal
===================
GlobalUpdatedGoal
=================

Checks if the global navigation goal has changed in the blackboard.
Returns failure if the goal is the same, if it changes, it returns success.
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
.. _bt_goal_updated_controller:

GoalUpdatedController
=====================

Checks if the global navigation goal, or a vector of goals, has changed in the blackboard. The node ticks its child if the goal was updated.

Input Ports
-----------

:goal:

=============================== ========
Type Default
------------------------------- --------
geometry_msgs::msg::PoseStamped "{goal}"
=============================== ========

Description
Destination to check. Takes in a blackboard variable, "{goal}" if not specified.

:goals:

==================================== =========
Type Default
------------------------------------ ---------
geometry_msgs::msg::PoseStampedArray "{goals}"
==================================== =========

Description
Vector of goals to check. Takes in a blackboard variable, "{goals}" if not specified.

Example
-------

.. code-block:: xml

<GoalUpdatedController goal="{goal}" goals="{goals}">
<!--Add tree components here--->
</GoalUpdatedController>
11 changes: 0 additions & 11 deletions configuration/packages/bt-plugins/decorators/SpeedController.rst
Original file line number Diff line number Diff line change
Expand Up @@ -55,17 +55,6 @@ Input Ports
Description
The maximum robot speed above which the child node is ticked at maximum rate (m/s).

:filter_duration:

====== =======
Type Default
------ -------
double 0.3
====== =======

Description
Duration (secs) over which robot velocity should be smoothed.

:goal:

=============================== ========
Expand Down
12 changes: 12 additions & 0 deletions configuration/packages/configuring-bt-navigator.rst
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,17 @@ Parameters
Description
Duration (in milliseconds) for each iteration of BT execution.

:filter_duration:

====== =======
Type Default
------ -------
double 0.3
====== =======

Description
Duration (secs) over which robot velocity should be smoothed.

:default_server_timeout:

==== =======
Expand Down Expand Up @@ -270,6 +281,7 @@ Example
global_frame: map
robot_base_frame: base_link
transform_tolerance: 0.1
filter_duration: 0.3
default_nav_to_pose_bt_xml: replace/with/path/to/bt.xml # or $(find-pkg-share my_package)/behavior_tree/my_nav_to_pose_bt.xml
default_nav_through_poses_bt_xml: replace/with/path/to/bt.xml # or $(find-pkg-share my_package)/behavior_tree/my_nav_through_poses_bt.xml
always_reload_bt_xml: false
Expand Down
3 changes: 2 additions & 1 deletion configuration/packages/configuring-bt-xml.rst
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ Condition Plugins
bt-plugins/conditions/TransformAvailable.rst
bt-plugins/conditions/DistanceTraveled.rst
bt-plugins/conditions/GoalUpdated.rst
bt-plugins/conditions/GloballyUpdatedGoal.rst
bt-plugins/conditions/GlobalUpdatedGoal.rst
bt-plugins/conditions/InitialPoseReceived.rst
bt-plugins/conditions/IsStuck.rst
bt-plugins/conditions/IsStopped.rst
Expand Down Expand Up @@ -101,6 +101,7 @@ Decorator Plugins
bt-plugins/decorators/GoalUpdater.rst
bt-plugins/decorators/PathLongerOnApproach.rst
bt-plugins/decorators/SingleTrigger.rst
bt-plugins/decorators/GoalUpdatedController.rst

Example
*******
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ PhotoAtWaypoint

Run-time plugin that takes photos at waypoint arrivals when using waypoint follower node. Saves the taken photos to specified directory. The name for taken photos are determined by
the waypoint index and timestamp(seconds). For instance ``/home/atas/0_1602582820.png`` is an sample taken image, where ``0_1602582820`` is the file name determined by waypoint
index and time stamp. The leading digit in file name implies the waypoint index and the rest of digits at righthand side imples the time stamp when the photo was taken.
index and time stamp. The leading digit in file name implies the waypoint index and the rest of digits at righthand side implies the time stamp when the photo was taken.

Parameters
**********
Expand Down
6 changes: 3 additions & 3 deletions migration/Humble.rst
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ Expanded Planner Benchmark Tests
Smac Planner Path Tolerances
****************************

`PR 3219 <https://github.com/ros-navigation/navigation2/pull/3219>`_ adds path tolerances to Hybrid-A* and State Lattice planners to return approximate paths if exact paths cannot be found, within a configurable tolerance aroun the goal pose.
`PR 3219 <https://github.com/ros-navigation/navigation2/pull/3219>`_ adds path tolerances to Hybrid-A* and State Lattice planners to return approximate paths if exact paths cannot be found, within a configurable tolerance around the goal pose.

costmap_2d_node default constructor
***********************************
Expand Down Expand Up @@ -125,8 +125,8 @@ Give Behavior Server Access to Both Costmaps

To update behaviors, any reference to the global_frame must be updated to the local_frame parameter
along with the ``configuration`` method which now takes in the local and global collision checkers.
Lastly, ``getResourceInfo`` must be overridden to return ``CostmapInfoType::LOCAL``. Other options include ``GLOBAL`` if the behavior useses global costmap and/or footprint)
or ``BOTH`` if both are required. This allows us to only create and maintain the minimum amount of expensive resources.
Lastly, ``getResourceInfo`` must be overridden to return ``CostmapInfoType::LOCAL``. Other options include ``GLOBAL`` if the behavior uses global costmap and/or footprint)
or ``BOTH`` if both are required. This allows us to only create and maintain the minimum amount of expensive resources.

New Model Predictive Path Integral Controller
*********************************************
Expand Down
2 changes: 1 addition & 1 deletion migration/Iron.rst
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ A new parameter ``enable_stamped_cmd_vel`` has been added to all of the publishe
Add VelocityPolygon in Collision Monitor
****************************************

`PR #3708 <https://github.com/ros-navigation/navigation2/pull/3708>`_ adds ``VelocityPolgon`` type in Collision Monitor. This allows the user to setup multiple polygons to cover the range of the robot's velocity limits. For example, the user can configure different polygons for rotation, moving forward, or moving backward. The Collision Monitor will check the robot's velocity against each sub polygon to determine the appropriate polygon to be used for collision checking. The tutorial is available in the :ref:`Configuring Collision Monitor with VelocityPolygon <collision_monitor_tutorial>` section.
`PR #3708 <https://github.com/ros-navigation/navigation2/pull/3708>`_ adds ``VelocityPolygon`` type in Collision Monitor. This allows the user to setup multiple polygons to cover the range of the robot's velocity limits. For example, the user can configure different polygons for rotation, moving forward, or moving backward. The Collision Monitor will check the robot's velocity against each sub polygon to determine the appropriate polygon to be used for collision checking. The tutorial is available in the :ref:`Configuring Collision Monitor with VelocityPolygon <collision_monitor_tutorial>` section.


Change polygon points parameter format in Collision Monitor
Expand Down
4 changes: 2 additions & 2 deletions plugin_tutorials/docs/writing_new_behavior_plugin.rst
Original file line number Diff line number Diff line change
Expand Up @@ -148,14 +148,14 @@ The remaining methods are not used and are not mandatory to override them.

Now that we have created our custom behavior, we need to export our Behavior Plugin so that it would be visible to the behavior server. Plugins are loaded at runtime and if they are not visible, then our behavior server won't be able to load it. In ROS 2, exporting and loading plugins is handled by ``pluginlib``.

Coming to our tutorial, class ``nav2_sms_bahavior::SendSms`` is loaded dynamically as ``nav2_core::Behavior`` which is our base class.
Coming to our tutorial, class ``nav2_sms_behavior::SendSms`` is loaded dynamically as ``nav2_core::Behavior`` which is our base class.

1. To export the behavior, we need to provide two lines

.. code-block:: c++

#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(nav2_sms_bahavior::SendSms, nav2_core::Behavior)
PLUGINLIB_EXPORT_CLASS(nav2_sms_behavior::SendSms, nav2_core::Behavior)

Note that it requires pluginlib to export out plugin's class. Pluginlib would provide as macro ``PLUGINLIB_EXPORT_CLASS`` which does all the work of exporting.

Expand Down
10 changes: 7 additions & 3 deletions plugins/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -478,7 +478,7 @@ Behavior Tree Nodes
| `Goal Updated Condition`_ |Aitor Miguel Blanco | Checks if goal is |
| | | preempted. |
+------------------------------------+--------------------+------------------------+
| `Globally Updated Goal Condition`_ | Joshua Wallace | Checks if goal is |
| `Global Updated Goal Condition`_ | Joshua Wallace | Checks if goal is |
| | | preempted in the global|
| | | BT context |
+------------------------------------+--------------------+------------------------+
Expand Down Expand Up @@ -547,15 +547,15 @@ Behavior Tree Nodes

.. _Goal Reached Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/goal_reached_condition.cpp
.. _Goal Updated Condition: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/condition/goal_updated_condition.cpp
.. _Globally Updated Goal Condition: https://github.com/navigation2/blob/replanning/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp
.. _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/navigation2/blob/replanning/nav2_behavior_tree/plugins/condition/is_path_valid_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.cpp
Expand Down Expand Up @@ -586,13 +586,17 @@ Behavior Tree Nodes
| | | larger than the old global path |
| | | on approach to the goal |
+--------------------------+---------------------+----------------------------------+
| `GoalUpdatedController`_ | Sophia Koffler | Ticks child node if the goal |
| | | has been updated |
+--------------------------+---------------------+----------------------------------+

.. _Rate Controller: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/decorator/rate_controller.cpp
.. _Distance Controller: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/decorator/distance_controller.cpp
.. _Speed Controller: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/decorator/speed_controller.cpp
.. _Goal Updater: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp
.. _Single Trigger: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/decorator/single_trigger_node.cpp
.. _PathLongerOnApproach: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.cpp
.. _GoalUpdatedController: https://github.com/ros-navigation/navigation2/blob/main/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp

+-----------------------+------------------------+----------------------------------+
| Control Plugin Name | Creator | Description |
Expand Down
2 changes: 1 addition & 1 deletion setup_guides/odom/setup_odom_gz.rst
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ Adding Gazebo Plugins to a URDF/SDF

We will now add the IMU sensor and the differential drive plugins of Gazebo to our URDF/SDF. For an overview of the different sensors available in Gazebo, have a look at the `Sensor Documentation <https://gazebosim.org/docs/latest/sensors>`_.

A sensor must be attached to a link, thus we will create an ``imu_link`` to which the IMU sensor will be attached. This link will be referenced under the ``<gazebo>`` element if using URDF. Next, we will set ``/demo/imu`` as the topic to which the IMU will be publishing its information, and we will comply with `REP145 <https://www.ros.org/reps/rep-0145.html>`_ by setting ``initalOrientationAsReference`` to ``false``. We will also add some noise to the sensor configuration using Gazebo's `sensor noise model <https://classic.gazebosim.org/tutorials?tut=sensor_noise>`_.
A sensor must be attached to a link, thus we will create an ``imu_link`` to which the IMU sensor will be attached. This link will be referenced under the ``<gazebo>`` element if using URDF. Next, we will set ``/demo/imu`` as the topic to which the IMU will be publishing its information, and we will comply with `REP145 <https://www.ros.org/reps/rep-0145.html>`_ by setting ``initialOrientationAsReference`` to ``false``. We will also add some noise to the sensor configuration using Gazebo's `sensor noise model <https://classic.gazebosim.org/tutorials?tut=sensor_noise>`_.

Now, we will set up our IMU sensor according to the description above.

Expand Down
2 changes: 1 addition & 1 deletion setup_guides/odom/setup_odom_gz_classic.rst
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ Adding Gazebo Plugins to a URDF

We will now add the IMU sensor and the differential drive plugins of Gazebo to our URDF. For an overview of the different plugins available in Gazebo, have a look at `Tutorial: Using Gazebo plugins with ROS <http://gazebosim.org/tutorials?tut=ros_gzplugins>`_.

For our robot, we will be using the `GazeboRosImuSensor <http://gazebosim.org/tutorials?tut=ros_gzplugins#IMUsensor(GazeboRosImuSensor)>`_ which is a SensorPlugin. A SensorPlugin must be attached to a link, thus we will create an ``imu_link`` to which the IMU sensor will be attached. This link will be referenced under the ``<gazebo>`` element. Next, we will set ``/demo/imu`` as the topic to which the IMU will be publishing its information, and we will comply with `REP145 <https://www.ros.org/reps/rep-0145.html>`_ by setting ``initalOrientationAsReference`` to ``false``. We will also add some noise to the sensor configuration using Gazebo's `sensor noise model <http://gazebosim.org/tutorials?tut=sensor_noise>`_.
For our robot, we will be using the `GazeboRosImuSensor <http://gazebosim.org/tutorials?tut=ros_gzplugins#IMUsensor(GazeboRosImuSensor)>`_ which is a SensorPlugin. A SensorPlugin must be attached to a link, thus we will create an ``imu_link`` to which the IMU sensor will be attached. This link will be referenced under the ``<gazebo>`` element. Next, we will set ``/demo/imu`` as the topic to which the IMU will be publishing its information, and we will comply with `REP145 <https://www.ros.org/reps/rep-0145.html>`_ by setting ``initialOrientationAsReference`` to ``false``. We will also add some noise to the sensor configuration using Gazebo's `sensor noise model <http://gazebosim.org/tutorials?tut=sensor_noise>`_.

Now, we will set up our IMU sensor plugin according to the description above by adding the following lines before the ``</robot>`` line in our URDF:

Expand Down
Loading