Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Check preempted in navigating to staging pose #57

Merged
merged 8 commits into from
Aug 7, 2024
Merged
Changes from 1 commit
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
Prev Previous commit
Next Next commit
Fix tests
Signed-off-by: redvinaa <redvinaa@gmail.com>
  • Loading branch information
redvinaa committed Aug 2, 2024
commit 365ea81ec41cc3ca9e38ee5f2b1a29745d9a84d6
19 changes: 15 additions & 4 deletions opennav_docking/test/test_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <functional>

#include "gtest/gtest.h"
#include "rclcpp/rclcpp.hpp"
#include "nav2_util/simple_action_server.hpp"
Expand Down Expand Up @@ -94,26 +96,35 @@ TEST(NavigatorTests, TestNavigator)
auto navigator = std::make_unique<Navigator>(node);
navigator->activate();

std::function<bool()> is_preempted_true = []() {return true;};
std::function<bool()> is_preempted_false = []() {return false;};

// Should succeed, action server set to succeed
dummy_navigator_node->setReturn(true);
EXPECT_NO_THROW(
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(10.0, 10.0)));
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(10.0, 10.0), is_preempted_false));

// Should fail, timeout exceeded
EXPECT_THROW(
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(0.0, 0.0)),
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(0.0, 0.0), is_preempted_false),
opennav_docking_core::FailedToStage);

// Should fail, action server set to succeed
dummy_navigator_node->setReturn(false);
EXPECT_THROW(
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(10.0, 10.0)),
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(10.0, 10.0), is_preempted_false),
opennav_docking_core::FailedToStage);

// First should fail, recursion should succeed
dummy_navigator_node->setToggle();
EXPECT_NO_THROW(
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(10.0, 10.0)));
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(10.0, 10.0), is_preempted_false));

// Should fail, preempted
dummy_navigator_node->setReturn(true);
EXPECT_THROW(
navigator->goToPose(geometry_msgs::msg::PoseStamped(), rclcpp::Duration(10.0, 10.0), is_preempted_true),
opennav_docking_core::FailedToStage);

navigator->deactivate();
navigator.reset();
Expand Down