Skip to content

Commit

Permalink
Update tests
Browse files Browse the repository at this point in the history
Signed-off-by: redvinaa <[email protected]>
  • Loading branch information
redvinaa committed Jul 3, 2024
1 parent f70ca5e commit 930ca12
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 3 deletions.
1 change: 1 addition & 0 deletions nav2_docking/opennav_docking/test/test_dock_file.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,3 +6,4 @@ docks:
dock2:
type: "dockv1"
pose: [0.0, 0.0, 0.4]
id: "2"
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@ TEST(SimpleChargingDockTests, RefinedPoseTest)

// Timestamps are outdated; this is after timeout
EXPECT_FALSE(dock->isDocked());
EXPECT_FALSE(dock->getRefinedPose(pose));
EXPECT_FALSE(dock->getRefinedPose(pose, ""));

geometry_msgs::msg::PoseStamped detected_pose;
detected_pose.header.stamp = node->now();
Expand All @@ -230,7 +230,7 @@ TEST(SimpleChargingDockTests, RefinedPoseTest)
rclcpp::spin_some(node->get_node_base_interface());

pose.header.frame_id = "my_frame";
EXPECT_TRUE(dock->getRefinedPose(pose));
EXPECT_TRUE(dock->getRefinedPose(pose, ""));
EXPECT_NEAR(pose.pose.position.x, 0.1, 0.01);
EXPECT_NEAR(pose.pose.position.y, -0.3, 0.01); // Applies external_detection_translation_x, +0.2

Expand Down
7 changes: 7 additions & 0 deletions nav2_docking/opennav_docking/test/test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,9 @@ TEST(UtilsTests, parseDockParams2)
node->declare_parameter("dockC.pose", rclcpp::ParameterValue(dock_pose));
node->declare_parameter("dockD.pose", rclcpp::ParameterValue(dock_pose));

// Don't declare C, check if empty string default
node->declare_parameter("dockD.id", rclcpp::ParameterValue("D"));

std::vector<std::string> docks_param;
node->get_parameter("docks", docks_param);

Expand All @@ -69,6 +72,8 @@ TEST(UtilsTests, parseDockParams2)
EXPECT_EQ(db["dockC"].type, std::string("typeA"));
EXPECT_EQ(db["dockC"].pose.position.x, 0.3);
EXPECT_EQ(db["dockC"].pose.position.y, 0.3);
EXPECT_EQ(db["dockC"].id, std::string(""));
EXPECT_EQ(db["dockD"].id, std::string("D"));
}

TEST(UtilsTests, parseDockParams3)
Expand Down Expand Up @@ -108,6 +113,8 @@ TEST(UtilsTests, parseDockFile)
EXPECT_EQ(db["dock2"].pose.position.x, 0.0);
EXPECT_EQ(db["dock2"].pose.position.y, 0.0);
EXPECT_NE(db["dock2"].pose.orientation.w, 1.0);
EXPECT_EQ(db["dock1"].id, std::string(""));
EXPECT_EQ(db["dock2"].id, std::string("2"));
}

TEST(UtilsTests, testgetDockPoseStamped)
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/opennav_docking/test/testing_dock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class TestFailureDock : public opennav_docking_core::ChargingDock
return geometry_msgs::msg::PoseStamped();
}

virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &)
virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &, std::string)
{
// Always return false to trigger a timeout, when no exceptions are thrown
return false;
Expand Down

0 comments on commit 930ca12

Please sign in to comment.