Skip to content

Commit 4d05d23

Browse files
authored
feat(opennav_docking): add on-demand detector client & unit tests for dock plugins (#5015) (#5218)
* feat(opennav_docking): Add dynamic lifecycle for external detectors This change introduces an API to dynamically enable and disable external docking detectors, such as those based on AI, to conserve system resources when not actively docking. Key changes: - Added `startDetectionProcess()` and `stopDetectionProcess()` to the docking plugin interface (`ChargingDock` and `NonChargingDock`). - Implemented this logic in `SimpleChargingDock` and `SimpleNonChargingDock` using a `std_srvs/Trigger` service call and dynamic topic subscription to manage the detector's lifecycle. - The `DockingServer` now ensures `stopDetectionProcess()` is called on all exit paths, including success, failure, and cancellation, to prevent dangling resources. - Added new parameters (`detector_service_name`, `subscribe_toggle`, etc.) to configure this behavior and updated the README documentation. - Added comprehensive C++ unit tests to verify the new detector lifecycle logic, specifically covering service failure cases and proper cleanup on action termination. Closes #5015 Signed-off-by: Koensgen Benjamin <[email protected]> - updtae Signed-off-by: Koensgen Benjamin <[email protected]> Signed-off-by: bkoensgen <[email protected]> * fix: Address review feedback and fix unit tests Signed-off-by: Koensgen Benjamin <[email protected]> fix(docking): Change subscribe_toggle default to false Signed-off-by: Koensgen Benjamin <[email protected]> - Signed-off-by: bkoensgen <[email protected]> * refactor(docking): Improve plugin lifecycle and resource management This commit addresses several code review suggestions to improve the design and robustness of the docking plugins. - Replaced the `DetectorState` enum with a simpler `bool detector_enabled_` for clarity. - Encapsulated the detection process lifecycle within the plugin itself. The `deactivate` method now ensures `stopDetectionProcess` is called, improving encapsulation and simplifying the `DockDatabase`. - Refactored the `configure` method in plugins to group related logic, improving readability. - Cleaned up redundant checks and calls in both the plugins and the `DockingServer` for more robust and intentional code. Signed-off-by: Koensgen Benjamin <[email protected]> Signed-off-by: bkoensgen <[email protected]> * fix(plugins): Resolve race condition by setting enabled state in callback The previous refactoring introduced a race condition where the detector was marked as 'enabled' in startDetection() before a message was actually received. This caused tests to fail because getRefinedPose() would be called with an enabled state but no valid/recent data. This commit fixes the issue by moving the `detector_enabled_ = true` assignment into the subscription callback. This ensures the plugin's state accurately reflects that it has received at least one valid data point before being considered active. Signed-off-by: Koensgen Benjamin <[email protected]> Signed-off-by: bkoensgen <[email protected]> * refactor(docking): migrate to nav2_ros_common (node_utils, LifecycleNode, QoS) Signed-off-by: bkoensgen <[email protected]> * build(opennav_docking): update deps (std_srvs, package.xml + CMakeLists) Signed-off-by: bkoensgen <[email protected]> * refactor(Docking): migrate to nav2::LifecycleNode Signed-off-by: bkoensgen <[email protected]> * refactor(docking): use nav2::qos::StandardTopicQoS for subscriptions Signed-off-by: bkoensgen <[email protected]> * refactor(opennav_docking): replace raw queue size with rclcpp::QoS(1) in pubs/subs Signed-off-by: bkoensgen <[email protected]> * refactor(tests): migrate nav2_util::NodeThread to nav2::NodeThread Signed-off-by: bkoensgen <[email protected]> * refactor(tests): migrate to 3-args service callbacks Signed-off-by: bkoensgen <[email protected]> * style(test): apply ament_uncrustify Signed-off-by: bkoensgen <[email protected]> * refactor(opennav_docking) migrate detector Trigger service to node_->create_client() Signed-off-by: bkoensgen <[email protected]> * docking: use nav2 types for pubs/subs in SimpleChargingDock and add explicit detection state flags Signed-off-by: bkoensgen <[email protected]> * docking: use nav2 types for pubs/subs in SimpleNonChargingDock and add explicit detection state flags Signed-off-by: bkoensgen <[email protected]> * docking: split detection state in SimpleChargingDock (detection_started_ vs initial_pose_received_) and warn before first pose Signed-off-by: bkoensgen <[email protected]> * docking: split detection state in SimpleNonChargingDock (detection_started_ vs initial_pose_received_) and warn before first pose Signed-off-by: bkoensgen <[email protected]> * tests: adapt SimpleChargingDockTestable to initial_pose_received_ state Signed-off-by: bkoensgen <[email protected]> * tests: adapt SimpleNonChargingDockTestable to initial_pose_received_ state Signed-off-by: bkoensgen <[email protected]> * docs(docking): clarify external detection gating and subscribe_toggle behavior (default=false) Signed-off-by: bkoensgen <[email protected]> * fix(docking): keep SimpleNonChargingDock registered as ChargingDock (stay in-scope) Signed-off-by: bkoensgen <[email protected]> * docs(docking): revert README note to pre-e881de19 state Signed-off-by: bkoensgen <[email protected]> * fix(docking_server): remove redundant null-check before stopDetectionProcess() in terminal cleanup Signed-off-by: bkoensgen <[email protected]> * style(docking_server): unify terminal order (stash->publishZeroVelocity->stopDetection->terminate) Signed-off-by: bkoensgen <[email protected]> * lint Signed-off-by: bkoensgen <[email protected]> * fix(docking): inline detection process Signed-off-by: bkoensgen <[email protected]> * chore(docking): drop redundant detector comment Signed-off-by: bkoensgen <[email protected]> * chore(docking): clarify detector logs Signed-off-by: bkoensgen <[email protected]> * fix(docking): activate lifecycle publishers Signed-off-by: bkoensgen <[email protected]> * chore(docking): reuse dock pose subscription Signed-off-by: bkoensgen <[email protected]> * lint Signed-off-by: bkoensgen <[email protected]> * fix(docking_server): drop redundant DB deactivate on cleanup Signed-off-by: bkoensgen <[email protected]> * refactor(docking): rename detection state flag to detection_active Signed-off-by: bkoensgen <[email protected]> * fix(docking): reset detection flags on cleanup Signed-off-by: bkoensgen <[email protected]> --------- Signed-off-by: Koensgen Benjamin <[email protected]> Signed-off-by: bkoensgen <[email protected]>
1 parent 2a803c2 commit 4d05d23

15 files changed

+1118
-95
lines changed

nav2_docking/README.md

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -36,12 +36,14 @@ The `ChargingDock` and `NonChargingDock` plugins are the heart of the customizab
3636
The docking procedure is as follows:
3737
1. Take action request and obtain the dock's plugin and its pose
3838
2. If the robot is not within the prestaging tolerance of the dock's staging pose, navigate to the staging pose
39-
3. Use the dock's plugin to initially detect the dock and return the docking pose
40-
4. Enter a vision-control loop where the robot attempts to reach the docking pose while its actively being refined by the vision system
41-
5. Exit the vision-control loop once contact has been detected or charging has started
42-
6. Wait until charging starts (if applicable) and return success.
39+
3. Call the dock's plugin `startDetectionProcess()` method to activate any external detection mechanisms.
40+
4. Use the dock's plugin to initially detect the dock (`getRefinedPose`) and return the docking pose.
41+
5. Enter a vision-control loop where the robot attempts to reach the docking pose while it's actively being refined by the vision system.
42+
6. Exit the vision-control loop once contact has been detected or charging has started (if applicable).
43+
7. Wait until charging starts (if applicable) and return success.
44+
8. Call the dock's plugin `stopDetectionProcess()` method to deactivate any external detection mechanisms.
4345

44-
If anywhere this procedure is unsuccessful, `N` retries may be made by driving back to the dock's staging pose and trying again. If still unsuccessful, it will return a failure code to indicate what kind of failure occurred to the client.
46+
If anywhere this procedure is unsuccessful (before step 8), `N` retries may be made, driving back to the dock's staging pose, and then restarting the process from step 3. If still unsuccessful after retries, it will return a failure code to indicate what kind of failure occurred to the client.
4547

4648
Undocking works more simply:
4749
1. If previously docked, use the known dock information to get the dock type. If not, use the undock action request's indicated dock type
@@ -175,8 +177,9 @@ some robots.
175177
`getStagingPose` applies a parameterized translational and rotational offset to the dock pose to obtain the staging pose.
176178

177179
`getRefinedPose` can be used in two ways.
178-
1. A blind approach where the returned dock pose will simply be equal to whatever was passed in from the dock database. This may work with a reduced success rate on a real robot (due to global localization error), but is useful for initial testing and simulation.
180+
1. A blind approach where the returned dock pose will simply be equal to whatever was passed in from the dock database. This may work with a reduced success rate on a real robot (due to global localization error), but is useful for initial testing and simulation. The `start/stopDetectionProcess` methods would typically do nothing in this case.
179181
2. The more realistic use case is to use an AR marker, dock pose detection algorithm, etc. The plugin will subscribe to a `geometry_msgs/PoseStamped` topic `detected_dock_pose`. This can be used with the `image_proc/TrackMarkerNode` for Apriltags or other custom detectors for your dock. It is unlikely the detected pose is actually the pose you want to dock with, so several parameters are supplied to represent your docked pose relative to the detected feature's pose.
182+
The subscription to `detected_dock_pose` can be managed dynamically (see `subscribe_toggle` parameter). Additionally, an external detector process can be triggered via a service call (see `detector_service_name`). The `DockingServer` calls `startDetectionProcess()` before `getRefinedPose` (which is called in a loop) and `stopDetectionProcess()` after the docking action concludes (successfully or not). This allows plugins to manage resources like GPU usage by only running detection when needed.
180183

181184
During the docking approach, there are two options for detecting `isDocked`:
182185
1. We can check the joint states of the wheels if the current has spiked above a set threshold to indicate that the robot has made contact with the dock or other physical object.
@@ -257,6 +260,9 @@ Note: `dock_plugins` and either `docks` or `dock_database` are required.
257260
| staging_yaw_offset | Staging pose angle relative to dock pose (rad) | double | 0.0 |
258261
| dock_direction | Whether the robot is docking with the dock forward or backward in motion | string | "forward" or "backward" |
259262
| rotate_to_dock | Enables backward docking without requiring a sensor for detection during the final approach. When enabled, the robot approaches the staging pose facing forward with sensor coverage for dock detection; after detection, it rotates and backs into the dock using only the initially detected pose for dead reckoning. | bool | false |
263+
| detector_service_name | Trigger service name to start/stop the detector (e.g., a camera node or an AprilTag detector node). Leave empty to disable service calls. | string | "" |
264+
| detector_service_timeout | Timeout (seconds) to wait for the detector service (if `detector_service_name` is set) to become available or respond. | double | 5.0 |
265+
| subscribe_toggle | If true, dynamically subscribe/unsubscribe to `detected_dock_pose` topic when `start/stopDetectionProcess` are called. If false, the subscription is kept alive throughout the plugin's lifecycle if `use_external_detection_pose` is true. This can be useful if the detector node is always running and publishing. | bool | false |
260266

261267
Note: The external detection rotation angles are setup to work out of the box with Apriltags detectors in `image_proc` and `isaac_ros`.
262268

nav2_docking/opennav_docking/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ find_package(rclcpp_components REQUIRED)
1818
find_package(rclcpp_lifecycle REQUIRED)
1919
find_package(rcl_interfaces REQUIRED)
2020
find_package(sensor_msgs REQUIRED)
21+
find_package(std_srvs REQUIRED)
2122
find_package(tf2 REQUIRED)
2223
find_package(tf2_geometry_msgs REQUIRED)
2324
find_package(tf2_ros REQUIRED)
@@ -127,6 +128,7 @@ target_link_libraries(simple_charging_dock PUBLIC
127128
rclcpp::rclcpp
128129
rclcpp_lifecycle::rclcpp_lifecycle
129130
${sensor_msgs_TARGETS}
131+
${std_srvs_TARGETS}
130132
tf2_geometry_msgs::tf2_geometry_msgs
131133
tf2_ros::tf2_ros
132134
nav2_ros_common::nav2_ros_common
@@ -155,6 +157,7 @@ target_link_libraries(simple_non_charging_dock PUBLIC
155157
rclcpp::rclcpp
156158
rclcpp_lifecycle::rclcpp_lifecycle
157159
${sensor_msgs_TARGETS}
160+
${std_srvs_TARGETS}
158161
tf2_geometry_msgs::tf2_geometry_msgs
159162
tf2_ros::tf2_ros
160163
)
@@ -211,6 +214,7 @@ ament_export_dependencies(
211214
rclcpp_action
212215
rclcpp_lifecycle
213216
rcl_interfaces
217+
std_srvs
214218
tf2_ros
215219
yaml-cpp
216220
)

nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp

Lines changed: 29 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <memory>
2020
#include <vector>
2121

22+
#include "std_srvs/srv/trigger.hpp"
2223
#include "geometry_msgs/msg/pose_stamped.hpp"
2324
#include "sensor_msgs/msg/battery_state.hpp"
2425
#include "sensor_msgs/msg/joint_state.hpp"
@@ -54,17 +55,17 @@ class SimpleChargingDock : public opennav_docking_core::ChargingDock
5455
/**
5556
* @brief Method to cleanup resources used on shutdown.
5657
*/
57-
virtual void cleanup() {}
58+
void cleanup() override;
5859

5960
/**
6061
* @brief Method to active Behavior and any threads involved in execution.
6162
*/
62-
virtual void activate() {}
63+
void activate() override;
6364

6465
/**
6566
* @brief Method to deactivate Behavior and any threads involved in execution.
6667
*/
67-
virtual void deactivate() {}
68+
void deactivate() override;
6869

6970
/**
7071
* @brief Method to obtain the dock's staging pose. This method should likely
@@ -104,14 +105,24 @@ class SimpleChargingDock : public opennav_docking_core::ChargingDock
104105
*/
105106
virtual bool hasStoppedCharging();
106107

108+
/**
109+
* @brief Start external detection process (service call + subscribe).
110+
*/
111+
bool startDetectionProcess() override;
112+
113+
/**
114+
* @brief Stop external detection process.
115+
*/
116+
bool stopDetectionProcess() override;
117+
107118
protected:
108119
void jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state);
109120

110121
// Optionally subscribe to a detected dock pose topic
111122
nav2::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_;
112-
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
113-
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
114-
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
123+
nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
124+
nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
125+
nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
115126
// If subscribed to a detected pose topic, will contain latest message
116127
geometry_msgs::msg::PoseStamped detected_dock_pose_;
117128
// This is the actual dock pose once it has the specified translation/rotation applied
@@ -150,6 +161,18 @@ class SimpleChargingDock : public opennav_docking_core::ChargingDock
150161

151162
nav2::LifecycleNode::SharedPtr node_;
152163
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
164+
165+
// Detector control parameters
166+
std::string detector_service_name_;
167+
double detector_service_timeout_{5.0};
168+
bool subscribe_toggle_{false};
169+
170+
// Client used to call the Trigger service
171+
nav2::ServiceClient<std_srvs::srv::Trigger>::SharedPtr detector_client_;
172+
173+
// Detection state flags
174+
bool detection_active_{false};
175+
bool initial_pose_received_{false};
153176
};
154177

155178
} // namespace opennav_docking

nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp

Lines changed: 35 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <memory>
2020
#include <vector>
2121

22+
#include "std_srvs/srv/trigger.hpp"
2223
#include "geometry_msgs/msg/pose_stamped.hpp"
2324
#include "sensor_msgs/msg/battery_state.hpp"
2425
#include "sensor_msgs/msg/joint_state.hpp"
@@ -54,17 +55,17 @@ class SimpleNonChargingDock : public opennav_docking_core::NonChargingDock
5455
/**
5556
* @brief Method to cleanup resources used on shutdown.
5657
*/
57-
virtual void cleanup() {}
58+
void cleanup() override;
5859

59-
/**
60-
* @brief Method to active Behavior and any threads involved in execution.
61-
*/
62-
virtual void activate() {}
60+
/**
61+
* @brief Method to active Behavior and any threads involved in execution.
62+
*/
63+
void activate() override;
6364

64-
/**
65-
* @brief Method to deactivate Behavior and any threads involved in execution.
66-
*/
67-
virtual void deactivate() {}
65+
/**
66+
* @brief Method to deactivate Behavior and any threads involved in execution.
67+
*/
68+
void deactivate() override;
6869

6970
/**
7071
* @brief Method to obtain the dock's staging pose. This method should likely
@@ -89,14 +90,24 @@ class SimpleNonChargingDock : public opennav_docking_core::NonChargingDock
8990
*/
9091
virtual bool isDocked();
9192

93+
/**
94+
* @brief Start external detection process (service call + subscribe).
95+
*/
96+
bool startDetectionProcess() override;
97+
98+
/**
99+
* @brief Stop external detection process.
100+
*/
101+
bool stopDetectionProcess() override;
102+
92103
protected:
93104
void jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state);
94105

95106
// Optionally subscribe to a detected dock pose topic
96107
nav2::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_;
97-
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
98-
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
99-
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
108+
nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
109+
nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
110+
nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
100111
// If subscribed to a detected pose topic, will contain latest message
101112
geometry_msgs::msg::PoseStamped detected_dock_pose_;
102113
// This is the actual dock pose once it has the specified translation/rotation applied
@@ -128,6 +139,18 @@ class SimpleNonChargingDock : public opennav_docking_core::NonChargingDock
128139

129140
nav2::LifecycleNode::SharedPtr node_;
130141
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
142+
143+
// Detector control parameters
144+
std::string detector_service_name_;
145+
double detector_service_timeout_{5.0};
146+
bool subscribe_toggle_{false};
147+
148+
// Client used to call the Trigger service
149+
nav2::ServiceClient<std_srvs::srv::Trigger>::SharedPtr detector_client_;
150+
151+
// Detection state flags
152+
bool detection_active_{false};
153+
bool initial_pose_received_{false};
131154
};
132155

133156
} // namespace opennav_docking

nav2_docking/opennav_docking/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
<depend>rclcpp_lifecycle</depend>
2626
<depend>rcl_interfaces</depend>
2727
<depend>sensor_msgs</depend>
28+
<depend>std_srvs</depend>
2829
<depend>tf2</depend>
2930
<depend>tf2_geometry_msgs</depend>
3031
<depend>tf2_ros</depend>

nav2_docking/opennav_docking/src/docking_server.cpp

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -331,6 +331,7 @@ void DockingServer::dockRobot()
331331
result->num_retries = num_retries_;
332332
stashDockData(goal->use_dock_id, dock, true);
333333
publishZeroVelocity();
334+
dock->plugin->stopDetectionProcess();
334335
docking_action_server_->succeeded_current(result);
335336
return;
336337
}
@@ -339,6 +340,7 @@ void DockingServer::dockRobot()
339340
// Cancelled, preempted, or shutting down (recoverable errors throw DockingException)
340341
stashDockData(goal->use_dock_id, dock, false);
341342
publishZeroVelocity();
343+
dock->plugin->stopDetectionProcess();
342344
docking_action_server_->terminate_all(result);
343345
return;
344346
} catch (opennav_docking_core::DockingException & e) {
@@ -354,6 +356,7 @@ void DockingServer::dockRobot()
354356
// Cancelled, preempted, or shutting down
355357
stashDockData(goal->use_dock_id, dock, false);
356358
publishZeroVelocity();
359+
dock->plugin->stopDetectionProcess();
357360
docking_action_server_->terminate_all(result);
358361
return;
359362
}
@@ -401,6 +404,7 @@ void DockingServer::dockRobot()
401404
stashDockData(goal->use_dock_id, dock, false);
402405
result->num_retries = num_retries_;
403406
publishZeroVelocity();
407+
dock->plugin->stopDetectionProcess();
404408
docking_action_server_->terminate_current(result);
405409
}
406410

@@ -429,12 +433,18 @@ Dock * DockingServer::generateGoalDock(std::shared_ptr<const DockRobot::Goal> go
429433
void DockingServer::doInitialPerception(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose)
430434
{
431435
publishDockingFeedback(DockRobot::Feedback::INITIAL_PERCEPTION);
436+
437+
if (!dock->plugin->startDetectionProcess()) {
438+
throw opennav_docking_core::FailedToDetectDock("Failed to start the detection process.");
439+
}
440+
432441
rclcpp::Rate loop_rate(controller_frequency_);
433442
auto start = this->now();
434443
auto timeout = rclcpp::Duration::from_seconds(initial_perception_timeout_);
435444
while (!dock->plugin->getRefinedPose(dock_pose, dock->id)) {
436445
if (this->now() - start > timeout) {
437-
throw opennav_docking_core::FailedToDetectDock("Failed initial dock detection");
446+
throw opennav_docking_core::FailedToDetectDock(
447+
"Failed initial dock detection: Timeout exceeded");
438448
}
439449

440450
if (checkAndWarnIfCancelled<DockRobot>(docking_action_server_, "dock_robot") ||

0 commit comments

Comments
 (0)