From 4c1feec390b1a83c70cace055efad290c0a00797 Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Wed, 11 Dec 2024 10:19:52 +0100 Subject: [PATCH 1/2] Update GoalUpdater docs Signed-off-by: Tony Najjar --- .../bt-plugins/decorators/GoalUpdater.rst | 37 ++++++++++++++++++- 1 file changed, 35 insertions(+), 2 deletions(-) diff --git a/configuration/packages/bt-plugins/decorators/GoalUpdater.rst b/configuration/packages/bt-plugins/decorators/GoalUpdater.rst index 82142a17f..6dc5d4ce1 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 - + From 239fb87ef6f92208ff176ef8097189137d22056c Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Thu, 12 Dec 2024 10:24:11 +0100 Subject: [PATCH 2/2] Update GoalUpdater.rst Signed-off-by: Tony Najjar --- .../packages/bt-plugins/decorators/GoalUpdater.rst | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/configuration/packages/bt-plugins/decorators/GoalUpdater.rst b/configuration/packages/bt-plugins/decorators/GoalUpdater.rst index 6dc5d4ce1..4a63a4b65 100644 --- a/configuration/packages/bt-plugins/decorators/GoalUpdater.rst +++ b/configuration/packages/bt-plugins/decorators/GoalUpdater.rst @@ -21,11 +21,11 @@ Parameters :goals_updater_topic: - ====== ============== + ====== =============== Type Default - ------ -------------- + ------ --------------- string "goals_update" - ====== ============== + ====== =============== Description The topic to receive the updated goals poses