Skip to content

Commit

Permalink
move make_lanelet function to autoware_test_utils
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <[email protected]>
  • Loading branch information
maxime-clem committed Nov 15, 2024
1 parent 549f706 commit 9d301f6
Show file tree
Hide file tree
Showing 3 changed files with 28 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -330,6 +330,19 @@ void updateNodeOptions(
*/
PathWithLaneId loadPathWithLaneIdInYaml();

/**
* @brief create a straight lanelet from 2 segments defined by 4 points
* @param [in] left0 start of the left segment
* @param [in] left1 end of the left segment
* @param [in] right0 start of the right segment
* @param [in] right1 end of the right segment
* @return a ConstLanelet with the given left and right bounds and a unique lanelet id
*
*/
lanelet::ConstLanelet make_lanelet(
const lanelet::BasicPoint2d & left0, const lanelet::BasicPoint2d & left1,
const lanelet::BasicPoint2d & right0, const lanelet::BasicPoint2d & right1);

/**
* @brief Generates a trajectory with specified parameters.
*
Expand Down
13 changes: 13 additions & 0 deletions common/autoware_test_utils/src/autoware_test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -313,6 +313,19 @@ PathWithLaneId loadPathWithLaneIdInYaml()
return parse<PathWithLaneId>(yaml_path);
}

lanelet::ConstLanelet make_lanelet(
const lanelet::BasicPoint2d & left0, const lanelet::BasicPoint2d & left1,
const lanelet::BasicPoint2d & right0, const lanelet::BasicPoint2d & right1)
{
lanelet::LineString3d left_bound;
left_bound.push_back(lanelet::Point3d(lanelet::InvalId, left0.x(), left0.y(), 0.0));
left_bound.push_back(lanelet::Point3d(lanelet::InvalId, left1.x(), left1.y(), 0.0));
lanelet::LineString3d right_bound;
right_bound.push_back(lanelet::Point3d(lanelet::InvalId, right0.x(), right0.y(), 0.0));
right_bound.push_back(lanelet::Point3d(lanelet::InvalId, right1.x(), right1.y(), 0.0));
return {lanelet::utils::getId(), left_bound, right_bound};
}

std::optional<std::string> resolve_pkg_share_uri(const std::string & uri_path)
{
std::smatch match;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,20 +36,9 @@
const auto intersection_map =
autoware::test_utils::make_map_bin_msg(autoware::test_utils::get_absolute_path_to_lanelet_map(
"autoware_test_utils", "intersection/lanelet2_map.osm"));
using autoware::behavior_path_planner::DrivableLanes;

lanelet::ConstLanelet make_lanelet(
const lanelet::BasicPoint2d & left0, const lanelet::BasicPoint2d & left1,
const lanelet::BasicPoint2d & right0, const lanelet::BasicPoint2d & right1)
{
lanelet::LineString3d left_bound;
left_bound.push_back(lanelet::Point3d(lanelet::InvalId, left0.x(), left0.y(), 0.0));
left_bound.push_back(lanelet::Point3d(lanelet::InvalId, left1.x(), left1.y(), 0.0));
lanelet::LineString3d right_bound;
right_bound.push_back(lanelet::Point3d(lanelet::InvalId, right0.x(), right0.y(), 0.0));
right_bound.push_back(lanelet::Point3d(lanelet::InvalId, right1.x(), right1.y(), 0.0));
return {lanelet::utils::getId(), left_bound, right_bound};
}
using autoware::behavior_path_planner::DrivableLanes;
using autoware::test_utils::make_lanelet;

DrivableLanes make_drivable_lanes(const lanelet::ConstLanelet & ll)
{
Expand Down

0 comments on commit 9d301f6

Please sign in to comment.