Skip to content

Commit

Permalink
add negated tests
Browse files Browse the repository at this point in the history
  • Loading branch information
robomic committed Oct 1, 2024
1 parent 9a15055 commit b1cc6da
Showing 1 changed file with 30 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2080,36 +2080,56 @@ TEST_F(HdMapUtilsTest_IntersectionMap, getLongitudinalDistance_laneChange)
const auto pose_from = traffic_simulator::helper::constructLaneletPose(563UL, 5.0);
const auto pose_to = traffic_simulator::helper::constructLaneletPose(659UL, 5.0);

const auto result = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
EXPECT_NO_THROW(EXPECT_NEAR(result.value(), 157.0, 1.0));
const auto without_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, false);
EXPECT_FALSE(without_lane_change.has_value());

const auto with_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
ASSERT_TRUE(with_lane_change.has_value());
EXPECT_NEAR(with_lane_change.value(), 157.0, 1.0);
}
{
const auto pose_from = traffic_simulator::helper::constructLaneletPose(563UL, 5.0);
const auto pose_to = traffic_simulator::helper::constructLaneletPose(658UL, 5.0);

const auto result = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
EXPECT_NO_THROW(EXPECT_NEAR(result.value(), 161.0, 1.0));
const auto without_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, false);
EXPECT_FALSE(without_lane_change.has_value());

const auto with_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
ASSERT_TRUE(with_lane_change.has_value());
EXPECT_NEAR(with_lane_change.value(), 161.0, 1.0);
}
{
const auto pose_from = traffic_simulator::helper::constructLaneletPose(563UL, 5.0);
const auto pose_to = traffic_simulator::helper::constructLaneletPose(657UL, 5.0);

const auto result = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
EXPECT_NO_THROW(EXPECT_NEAR(result.value(), 161.0, 1.0));
const auto without_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, false);
EXPECT_FALSE(without_lane_change.has_value());

const auto with_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
ASSERT_TRUE(with_lane_change.has_value());
EXPECT_NEAR(with_lane_change.value(), 161.0, 1.0);
}
{
const auto pose_from = traffic_simulator::helper::constructLaneletPose(643UL, 5.0);
const auto pose_to = traffic_simulator::helper::constructLaneletPose(666UL, 5.0);

const auto result = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
EXPECT_NO_THROW(EXPECT_NEAR(result.value(), 250.0, 1.0));
const auto without_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, false);
EXPECT_FALSE(without_lane_change.has_value());

const auto with_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
ASSERT_TRUE(with_lane_change.has_value());
EXPECT_NEAR(with_lane_change.value(), 250.0, 1.0);
}
{
const auto pose_from = traffic_simulator::helper::constructLaneletPose(643UL, 5.0);
const auto pose_to = traffic_simulator::helper::constructLaneletPose(665UL, 5.0);

const auto result = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
EXPECT_NO_THROW(EXPECT_NEAR(result.value(), 253.0, 1.0));
const auto without_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, false);
EXPECT_FALSE(without_lane_change.has_value());

const auto with_lane_change = hdmap_utils.getLongitudinalDistance(pose_from, pose_to, true);
ASSERT_TRUE(with_lane_change.has_value());
EXPECT_NEAR(with_lane_change.value(), 253.0, 1.0);
}
}

Expand Down

0 comments on commit b1cc6da

Please sign in to comment.