diff --git a/configuration/packages/bt-plugins/actions/DockRobot.rst b/configuration/packages/bt-plugins/actions/DockRobot.rst
new file mode 100644
index 000000000..74864555d
--- /dev/null
+++ b/configuration/packages/bt-plugins/actions/DockRobot.rst
@@ -0,0 +1,120 @@
+.. _bt_dock_robot_action:
+
+DockRobot
+=========
+
+Invokes the DockRobot ROS 2 action server, which is implemented by the docking server.
+
+It is used to dock the robot to a docking station.
+
+Input Ports
+***********
+
+:use_dock_id:
+
+ ==== =======
+ Type Default
+ ---- -------
+ bool true
+ ==== =======
+
+ Description
+ Whether to use the dock's ID or dock pose fields.
+
+:dock_id:
+
+ ====== =======
+ Type Default
+ ------ -------
+ string N/A
+ ====== =======
+
+ Description
+ Dock ID or name to use.
+
+:dock_pose:
+
+ ========================= =======
+ Type Default
+ ------------------------- -------
+ geometry_msgs/PoseStamped N/A
+ ========================= =======
+
+ Description
+ The dock pose, if not using dock id.
+
+:dock_type:
+
+ ====== =======
+ Type Default
+ ------ -------
+ string N/A
+ ====== =======
+
+ Description
+ The dock plugin type, if using dock pose.
+
+:max_staging_time:
+
+ ===== =======
+ Type Default
+ ----- -------
+ float 1000.0
+ ===== =======
+
+ Description
+ Maximum time to navigate to the staging pose.
+
+:navigate_to_staging_pose:
+
+ ==== =======
+ Type Default
+ ---- -------
+ bool true
+ ==== =======
+
+ Description
+ Whether to autonomously navigate to staging pose.
+
+Output Ports
+------------
+
+:success:
+
+ ==== =======
+ Type Default
+ ---- -------
+ bool true
+ ==== =======
+
+ Description
+ If the action was successful.
+
+:error_code_id:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ uint16 0
+ ============== =======
+
+ Description
+ Dock robot error code. See ``DockRobot`` action message for the enumerated set of error codes.
+
+:num_retries:
+
+ ====== =======
+ Type Default
+ ------ -------
+ uint16 0
+ ====== =======
+
+ Description
+ The number of retries executed.
+
+Example
+-------
+
+.. code-block:: xml
+
+
diff --git a/configuration/packages/bt-plugins/actions/UndockRobot.rst b/configuration/packages/bt-plugins/actions/UndockRobot.rst
new file mode 100644
index 000000000..6125d305e
--- /dev/null
+++ b/configuration/packages/bt-plugins/actions/UndockRobot.rst
@@ -0,0 +1,65 @@
+.. _bt_undock_robot_action:
+
+UndockRobot
+===========
+
+Invokes the UndockRobot ROS 2 action server, which is implemented by the docking server.
+
+It is used to undock the robot from a docking station.
+
+Input Ports
+***********
+
+:dock_type:
+
+ ====== =======
+ Type Default
+ ------ -------
+ string N/A
+ ====== =======
+
+ Description
+ The dock plugin type, if not previous instance used for docking.
+
+:max_undocking_time:
+
+ ===== =======
+ Type Default
+ ----- -------
+ float 30.0
+ ===== =======
+
+ Description
+ Maximum time to get back to the staging pose.
+
+Output Ports
+------------
+
+:success:
+
+ ==== =======
+ Type Default
+ ---- -------
+ bool true
+ ==== =======
+
+ Description
+ If the action was successful.
+
+:error_code_id:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ uint16 0
+ ============== =======
+
+ Description
+ Dock robot error code. See ``UndockRobot`` action message for the enumerated set of error codes.
+
+Example
+-------
+
+.. code-block:: xml
+
+
diff --git a/configuration/packages/configuring-bt-xml.rst b/configuration/packages/configuring-bt-xml.rst
index f08349010..ce1c669c7 100644
--- a/configuration/packages/configuring-bt-xml.rst
+++ b/configuration/packages/configuring-bt-xml.rst
@@ -51,6 +51,8 @@ Action Plugins
bt-plugins/actions/CancelAssistedTeleop.rst
bt-plugins/actions/Smooth.rst
bt-plugins/actions/GetPoseFromPath.rst
+ bt-plugins/actions/DockRobot.rst
+ bt-plugins/actions/UndockRobot.rst
Condition Plugins
*****************
diff --git a/plugins/index.rst b/plugins/index.rst
index 675151f07..62a3fb386 100644
--- a/plugins/index.rst
+++ b/plugins/index.rst
@@ -412,6 +412,10 @@ Behavior Tree Nodes
+--------------------------------------------+---------------------+------------------------------------------+
| `Get Pose From Path Action`_ | Marc Morcos | Extracts a pose from a path |
+--------------------------------------------+---------------------+------------------------------------------+
+| `Dock Robot Action`_ | Steve Macenski | Calls dock robot action |
++--------------------------------------------+---------------------+------------------------------------------+
+| `Undock Robot Action`_ | Steve Macenski | Calls undock robot action |
++--------------------------------------------+---------------------+------------------------------------------+
.. _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
@@ -445,6 +449,8 @@ Behavior Tree Nodes
.. _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
+.. _Dock Robot Action: https://github.com/ros-navigation/navigation2/blob/main/nav2_docking/opennav_docking_bt/src/dock_robot.cpp
+.. _Undock Robot Action: https://github.com/ros-navigation/navigation2/blob/main/nav2_docking/opennav_docking_bt/src/undock_robot.cpp
+------------------------------------+--------------------+------------------------+