Skip to content

Commit

Permalink
Update GoalUpdater docs (#621)
Browse files Browse the repository at this point in the history
* Update GoalUpdater docs

Signed-off-by: Tony Najjar <[email protected]>

* Update GoalUpdater.rst

Signed-off-by: Tony Najjar <[email protected]>

* add migration guide

Signed-off-by: Tony Najjar <[email protected]>

---------

Signed-off-by: Tony Najjar <[email protected]>
  • Loading branch information
tonynajjar authored Jan 14, 2025
1 parent d9302ff commit 90c2e60
Show file tree
Hide file tree
Showing 2 changed files with 41 additions and 4 deletions.
37 changes: 35 additions & 2 deletions configuration/packages/bt-plugins/decorators/GoalUpdater.rst
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
GoalUpdater
===========

A custom control node, which updates the goal pose. It subscribes to a topic in which it can receive an updated goal pose to use instead of the one commanded in action. It is useful for dynamic object following tasks.
A custom control node, which updates the goal(s) pose(s). It subscribes to a topic in which it can receive (an) updated goal(s) pose(s) to use instead of the one(s) commanded in action. It is useful for dynamic object following tasks.

Parameters
----------
Expand All @@ -19,6 +19,17 @@ Parameters
Description
The topic to receive the updated goal pose

:goals_updater_topic:

====== ===============
Type Default
------ ---------------
string "goals_update"
====== ===============

Description
The topic to receive the updated goals poses

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

Expand All @@ -33,6 +44,17 @@ Input Ports
Description
The original goal pose

:input_goals:

============================== =======
Type Default
------------------------------ -------
geometry_msgs/PoseStampedArray N/A
============================== =======

Description
The original goals poses

:output_goal:

========================= =======
Expand All @@ -44,11 +66,22 @@ Input Ports
Description
The resulting updated goal. If no goal received by subscription, it will be the input_goal

:output_goals:

============================== =======
Type Default
------------------------------ -------
geometry_msgs/PoseStampedArray N/A
============================== =======

Description
The resulting updated goals. If no goals received by subscription, it will be the input_goals

Example
-------

.. code-block:: xml
<GoalUpdater input_goal="{goal}" output_goal="{updated_goal}">
<GoalUpdater input_goal="{goal}" input_goals="{goals}" output_goal="{goal}" output_goals="{goals}">
<!--Add tree components here--->
</GoalUpdater>
8 changes: 6 additions & 2 deletions migration/Jazzy.rst
Original file line number Diff line number Diff line change
Expand Up @@ -51,15 +51,19 @@ Here we can see the working demo of the plugin:

.. attention:: If the docking server is unavailable, then the combo box of the dock type will be empty.

New BT Nodes
************
BT Nodes Changes
****************

Below is a list of new BT Nodes added:

- ``GetPoseFromPath``: An action to get a particular pose from an input path.
- ``RemoveInCollisionGoals``: An action to remove waypoints that have a cost higher than a threshold.
- ``IsStopped``: A condition to check if the robot is stopped for a certain duration.

Below is a list of changes to existing BT Nodes:

- ``GoalUpdater``: It now supports updating a list of goals as well (useful for NavigateThroughPoses interface)

New RViz Tool for Costmap Cost Cell Inspection
**********************************************

Expand Down

0 comments on commit 90c2e60

Please sign in to comment.