diff --git a/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp b/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp
index 1b8f6517f66..e24b3b251e1 100644
--- a/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp
+++ b/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp
@@ -109,7 +109,7 @@ TEST_F(SpinActionTestFixture, test_ports)
R"(
-
+
)";
diff --git a/nav2_core/include/nav2_core/progress_checker.hpp b/nav2_core/include/nav2_core/progress_checker.hpp
index 041ae88fbdb..2dd9c5bef89 100644
--- a/nav2_core/include/nav2_core/progress_checker.hpp
+++ b/nav2_core/include/nav2_core/progress_checker.hpp
@@ -55,7 +55,7 @@ class ProgressChecker
/**
* @brief Reset class state upon calling
*/
- virtual void reset() {}
+ virtual void reset() = 0;
};
} // namespace nav2_core
diff --git a/nav2_util/CMakeLists.txt b/nav2_util/CMakeLists.txt
index 21be6cdfa95..930034f09cf 100644
--- a/nav2_util/CMakeLists.txt
+++ b/nav2_util/CMakeLists.txt
@@ -17,6 +17,7 @@ find_package(rclcpp_lifecycle REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(bondcpp REQUIRED)
find_package(bond REQUIRED)
+find_package(action_msgs REQUIRED)
set(dependencies
nav2_msgs
@@ -32,6 +33,7 @@ set(dependencies
rclcpp_lifecycle
bondcpp
bond
+ action_msgs
)
nav2_package()
diff --git a/nav2_util/package.xml b/nav2_util/package.xml
index 87f9086b9c2..8d5ccf865c6 100644
--- a/nav2_util/package.xml
+++ b/nav2_util/package.xml
@@ -28,6 +28,7 @@
rclcpp_lifecycle
launch
launch_testing_ament_cmake
+ action_msgs
libboost-program-options
@@ -37,6 +38,7 @@
launch
launch_testing_ament_cmake
std_srvs
+ action_msgs
ament_cmake
diff --git a/nav2_util/test/test_actions.cpp b/nav2_util/test/test_actions.cpp
index b999a28b7c9..35043d5df2f 100644
--- a/nav2_util/test/test_actions.cpp
+++ b/nav2_util/test/test_actions.cpp
@@ -516,6 +516,31 @@ TEST_F(ActionTest, test_handle_goal_deactivated)
SUCCEED();
}
+TEST_F(ActionTest, test_handle_cancel)
+{
+ auto goal = Fibonacci::Goal();
+ goal.order = 14000000;
+
+ // Send the goal
+ auto future_goal_handle = node_->action_client_->async_send_goal(goal);
+ EXPECT_EQ(
+ rclcpp::spin_until_future_complete(
+ node_,
+ future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
+
+ // Cancel the goal
+ auto cancel_response = node_->action_client_->async_cancel_goal(future_goal_handle.get());
+ EXPECT_EQ(
+ rclcpp::spin_until_future_complete(
+ node_,
+ cancel_response), rclcpp::FutureReturnCode::SUCCESS);
+
+ // Check cancelled
+ EXPECT_EQ(future_goal_handle.get()->get_status(), rclcpp_action::GoalStatus::STATUS_CANCELING);
+
+ SUCCEED();
+}
+
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);