Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ TEST_F(SpinActionTestFixture, test_ports)
R"(
<root main_tree_to_execute = "MainTree" >
<BehaviorTree ID="MainTree">
<Spin />
<Spin server_name="spin"/>
</BehaviorTree>
</root>)";

Expand Down
2 changes: 1 addition & 1 deletion nav2_core/include/nav2_core/progress_checker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class ProgressChecker
/**
* @brief Reset class state upon calling
*/
virtual void reset() {}
virtual void reset() = 0;
};
} // namespace nav2_core

Expand Down
2 changes: 2 additions & 0 deletions nav2_util/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -32,6 +33,7 @@ set(dependencies
rclcpp_lifecycle
bondcpp
bond
action_msgs
)

nav2_package()
Expand Down
2 changes: 2 additions & 0 deletions nav2_util/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
<depend>rclcpp_lifecycle</depend>
<depend>launch</depend>
<depend>launch_testing_ament_cmake</depend>
<depend>action_msgs</depend>

<exec_depend>libboost-program-options</exec_depend>

Expand All @@ -37,6 +38,7 @@
<test_depend>launch</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>std_srvs</test_depend>
<test_depend>action_msgs</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
25 changes: 25 additions & 0 deletions nav2_util/test/test_actions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down