diff --git a/configuration/packages/bt-plugins/decorators/GoalUpdater.rst b/configuration/packages/bt-plugins/decorators/GoalUpdater.rst index 82142a17f..4a63a4b65 100644 --- a/configuration/packages/bt-plugins/decorators/GoalUpdater.rst +++ b/configuration/packages/bt-plugins/decorators/GoalUpdater.rst @@ -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 ---------- @@ -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 ----------- @@ -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: ========================= ======= @@ -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 - + diff --git a/migration/Jazzy.rst b/migration/Jazzy.rst index 9cd47768c..554eb1708 100644 --- a/migration/Jazzy.rst +++ b/migration/Jazzy.rst @@ -51,8 +51,8 @@ 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: @@ -60,6 +60,10 @@ Below is a list of new BT Nodes added: - ``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 **********************************************