Skip to content

Commit

Permalink
Merge branch 'main' into agalbachicar/#543_routing_part_four
Browse files Browse the repository at this point in the history
  • Loading branch information
agalbachicar authored Jun 11, 2024
2 parents 9becab8 + 98fa460 commit 270ada6
Show file tree
Hide file tree
Showing 4 changed files with 56 additions and 4 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@ jobs:
container:
image: ubuntu:20.04
steps:
- uses: actions/checkout@v3
- uses: actions/checkout@v4
- uses: ros-tooling/[email protected]
- uses: ros-tooling/action-ros-ci@v0.2
- uses: ros-tooling/action-ros-ci@v0.3
id: action_ros_ci_step
with:
package-name: ${{ env.PACKAGE_NAME }}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/sanitizers.yml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ jobs:
- uses: ros-tooling/[email protected]
env:
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
- uses: actions/checkout@v3
- uses: actions/checkout@v4
with:
path: ${{ env.ROS_WS }}/src/${{ env.PACKAGE_NAME }}
- name: clang 8 install
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/scan_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ jobs:
- uses: ros-tooling/[email protected]
env:
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
- uses: actions/checkout@v3
- uses: actions/checkout@v4
with:
path: ${{ env.ROS_WS }}/src/${{ env.PACKAGE_NAME }}
- name: clang 8 install
Expand Down
52 changes: 52 additions & 0 deletions test/find_lane_sequences_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,9 @@
#include <maliput/api/road_geometry.h>
#include <maliput/common/filesystem.h>
#include <maliput_dragway_test_utilities/fixtures.h>
#include <maliput_malidrive/builder/params.h>
#include <maliput_malidrive/builder/road_network_builder.h>
#include <maliput_malidrive/loader/loader.h>
#include <maliput_multilane/builder.h>
#include <maliput_multilane/loader.h>
#include <maliput_multilane_test_utilities/fixtures.h>
Expand Down Expand Up @@ -190,5 +193,54 @@ GTEST_TEST(FindLaneSequencesTest, MaxLengthOmitsStartAndEndLanes) {
ASSERT_EQ(FindLaneSequences(start_lane, end_lane, total_length).size(), 1u);
}

static constexpr char kMalidriveResourcesPath[] = DEF_MALIDRIVE_RESOURCES;

// Loads TShapeRoad, and evaluates FindLaneSequences() for a large distance that will not
// filter out results, and shows the behavior when removing and leaving U-turns.
class TShapeRoadFindLaneSequencesTest : public ::testing::Test {
public:
//@{ Tolerances set to match the involved geometries and the parser resolution.
static constexpr double kLinearTolerance{1e-6};
static constexpr double kAngularTolerance{1e-6};
static constexpr double kScaleLength{1.0};
static constexpr double kDistance{std::numeric_limits<double>::max()};
static constexpr bool kDontRemoveUTurns{false};
static constexpr bool kRemoveUTurns{true};
//@}
const std::string kTShapeRoadFilePath{std::string(kMalidriveResourcesPath) +
std::string("/resources/odr/TShapeRoad.xodr")};

const api::LaneId kStartLaneId{"1_0_1"};
const api::LaneId kEndLaneId{"0_0_1"};
const Lane* start_lane_;
const Lane* end_lane_;

void SetUp() override {
std::map<std::string, std::string> configuration;
configuration.emplace(malidrive::builder::params::kRoadGeometryId, "malidrive_rg");
configuration.emplace(malidrive::builder::params::kOpendriveFile, kTShapeRoadFilePath);
configuration.emplace(malidrive::builder::params::kLinearTolerance, std::to_string(kLinearTolerance));
configuration.emplace(malidrive::builder::params::kAngularTolerance, std::to_string(kAngularTolerance));
configuration.emplace(malidrive::builder::params::kScaleLength, std::to_string(kScaleLength));
configuration.emplace(malidrive::builder::params::kInertialToBackendFrameTranslation, "{0., 0., 0.}");
road_network_ = malidrive::loader::Load<malidrive::builder::RoadNetworkBuilder>(configuration);
start_lane_ = road_network_->road_geometry()->ById().GetLane(kStartLaneId);
end_lane_ = road_network_->road_geometry()->ById().GetLane(kEndLaneId);
}

std::unique_ptr<api::RoadNetwork> road_network_{};
};

TEST_F(TShapeRoadFindLaneSequencesTest, NotRemovingUTurnYieldsTwoSequences) {
CheckSequences(
FindLaneSequences(start_lane_, end_lane_, kDistance, kDontRemoveUTurns),
{{"1_0_1", "6_0_-1", "2_0_1", "9_0_-1", "0_0_-1", "5_0_-1", "1_0_-1", "7_0_-1", "2_0_-1", "8_0_-1", "0_0_1"},
{"1_0_1", "4_0_1", "0_0_1"}});
}

TEST_F(TShapeRoadFindLaneSequencesTest, RemovingUTurnYieldsOneSequence) {
CheckSequences(FindLaneSequences(start_lane_, end_lane_, kDistance, kRemoveUTurns), {{"1_0_1", "4_0_1", "0_0_1"}});
}

} // namespace routing
} // namespace maliput

0 comments on commit 270ada6

Please sign in to comment.