From 81f19e4384f50801a62644238f68fa192b662b05 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 9 Jul 2024 11:50:31 -0700 Subject: [PATCH] adding get pose from path (#574) --- .../bt-plugins/actions/GetPoseFromPath.rst | 52 +++++++++++++++++++ configuration/packages/configuring-bt-xml.rst | 1 + migration/Jazzy.rst | 9 +++- plugins/index.rst | 3 ++ 4 files changed, 64 insertions(+), 1 deletion(-) create mode 100644 configuration/packages/bt-plugins/actions/GetPoseFromPath.rst diff --git a/configuration/packages/bt-plugins/actions/GetPoseFromPath.rst b/configuration/packages/bt-plugins/actions/GetPoseFromPath.rst new file mode 100644 index 000000000..7a366653c --- /dev/null +++ b/configuration/packages/bt-plugins/actions/GetPoseFromPath.rst @@ -0,0 +1,52 @@ +.. _bt_getposefrompath_action: + +GetPoseFromPath +=============== + +Gets a pose from a particular index on the path. Use ``-1`` to get the last pose, ``-2`` for second to last, and so on. + +Input Ports +*********** + +:path: + + ============= ======= + Type Default + ------------- ------- + nav_msgs/Path N/A + ============= ======= + + Description + Path to extract pose from + +:index: + + ====== ======= + Type Default + ------ ------- + int 0 + ====== ======= + + Description + Index from path to use. Use ``-1`` to get the last pose, ``-2`` for second to last, and so on. + +Output Ports +------------ + +:pose: + + ========================= ======= + Type Default + ------------------------- ------- + geometry_msgs/PoseStamped N/A + ========================= ======= + + Description + Pose from path, with the Path's set header. + +Example +------- + +.. code-block:: xml + + diff --git a/configuration/packages/configuring-bt-xml.rst b/configuration/packages/configuring-bt-xml.rst index 7a4f43d9d..f08349010 100644 --- a/configuration/packages/configuring-bt-xml.rst +++ b/configuration/packages/configuring-bt-xml.rst @@ -50,6 +50,7 @@ Action Plugins bt-plugins/actions/CancelDriveOnHeading.rst bt-plugins/actions/CancelAssistedTeleop.rst bt-plugins/actions/Smooth.rst + bt-plugins/actions/GetPoseFromPath.rst Condition Plugins ***************** diff --git a/migration/Jazzy.rst b/migration/Jazzy.rst index 93832da0f..10653623b 100644 --- a/migration/Jazzy.rst +++ b/migration/Jazzy.rst @@ -23,4 +23,11 @@ Here we can see the working demo of the plugin: .. image:: images/docking_panel.gif -.. attention:: If the docking server is unavailable, then the combo box of the dock type will be empty. \ No newline at end of file +.. attention:: If the docking server is unavailable, then the combo box of the dock type will be empty. + +New BT Nodes +************ + +Below is a list of new BT Nodes added: + +- ``GetPoseFromPath``: An action to get a particular pose from an input path. diff --git a/plugins/index.rst b/plugins/index.rst index 9c2729f6d..675151f07 100644 --- a/plugins/index.rst +++ b/plugins/index.rst @@ -410,6 +410,8 @@ Behavior Tree Nodes +--------------------------------------------+---------------------+------------------------------------------+ | `Compute Complete Coverage Path Action`_ | Steve Macenski | Calls coverage planner server | +--------------------------------------------+---------------------+------------------------------------------+ +| `Get Pose From Path Action`_ | Marc Morcos | Extracts a pose from a path | ++--------------------------------------------+---------------------+------------------------------------------+ .. _Back Up Action: https://github.com/ros-planning/navigation2/tree/main/nav2_behavior_tree/plugins/action/back_up_action.cpp .. _Drive On Heading Action: https://github.com/ros-planning/navigation2/tree/main/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp @@ -442,6 +444,7 @@ Behavior Tree Nodes .. _Cancel Assisted Teleop Action: https://github.com/ros-planning/navigation2/tree/main/nav2_behavior_tree/plugins/action/assisted_teleop_cancel_node.cpp .. _Cancel Complete Coverage Action: https://github.com/open-navigation/opennav_coverage/blob/main/opennav_coverage_bt/src/cancel_complete_coverage_path.cpp .. _Compute Complete Coverage Path Action: https://github.com/open-navigation/opennav_coverage/blob/main/opennav_coverage_bt/src/compute_complete_coverage_path.cpp +.. _Get Pose From Path Action: https://github.com/ros-navigation/navigation2/blob/main/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp +------------------------------------+--------------------+------------------------+