Skip to content

Commit

Permalink
refactor(autoware_test_utils): enhance makeMapBinMsg to accept packag…
Browse files Browse the repository at this point in the history
…e name and map filename parameters (autowarefoundation#9617)

* feat: enhance makeMapBinMsg to accept package name and map filename parameters

Signed-off-by: kyoichi-sugahara <[email protected]>

* feat: set default package name to 'autoware_test_utils' in makeMapBinMsg and related functions

Signed-off-by: kyoichi-sugahara <[email protected]>

---------

Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara authored Dec 12, 2024
1 parent 3c94dbf commit 41ca768
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -213,15 +213,21 @@ LaneletMapBin make_map_bin_msg(
const std::string & absolute_path, const double center_line_resolution = 5.0);

/**
* @brief Creates a LaneletMapBin message using a predefined Lanelet2 map file.
* @brief Creates a LaneletMapBin message using a Lanelet2 map file.
*
* This function loads a lanelet2_map.osm from the test_map folder in the
* autoware_test_utils package, overwrites the centerline with a resolution of 5.0,
* This function loads a specified map file from the test_map folder in the
* specified package (or autoware_test_utils if no package is specified),
* overwrites the centerline with a resolution of 5.0,
* and converts the map to a LaneletMapBin message.
*
* @param package_name The name of the package containing the map file. If empty, defaults to
* "autoware_test_utils".
* @param map_filename The name of the map file (e.g. "lanelet2_map.osm")
* @return A LaneletMapBin message containing the map data.
*/
LaneletMapBin makeMapBinMsg();
LaneletMapBin makeMapBinMsg(
const std::string & package_name = "autoware_test_utils",
const std::string & map_filename = "lanelet2_map.osm");

/**
* @brief Creates an Odometry message with a specified shift.
Expand Down
5 changes: 2 additions & 3 deletions common/autoware_test_utils/src/autoware_test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,10 +180,9 @@ LaneletMapBin make_map_bin_msg(
return map_bin_msg;
}

LaneletMapBin makeMapBinMsg()
LaneletMapBin makeMapBinMsg(const std::string & package_name, const std::string & map_filename)
{
return make_map_bin_msg(
get_absolute_path_to_lanelet_map("autoware_test_utils", "lanelet2_map.osm"));
return make_map_bin_msg(get_absolute_path_to_lanelet_map(package_name, map_filename));
}

Odometry makeOdometry(const double shift)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

#include <iostream>
#include <memory>
#include <string>
#include <vector>

namespace autoware_planning_test_manager::utils
Expand All @@ -34,9 +35,11 @@ using geometry_msgs::msg::Pose;
using nav_msgs::msg::Odometry;
using RouteSections = std::vector<autoware_planning_msgs::msg::LaneletSegment>;

Pose createPoseFromLaneID(const lanelet::Id & lane_id)
Pose createPoseFromLaneID(
const lanelet::Id & lane_id, const std::string & package_name = "autoware_test_utils",
const std::string & map_filename = "lanelet2_map.osm")
{
auto map_bin_msg = autoware::test_utils::makeMapBinMsg();
auto map_bin_msg = autoware::test_utils::makeMapBinMsg(package_name, map_filename);
// create route_handler
auto route_handler = std::make_shared<RouteHandler>();
route_handler->setMap(map_bin_msg);
Expand Down Expand Up @@ -67,16 +70,19 @@ Pose createPoseFromLaneID(const lanelet::Id & lane_id)

// Function to create a route from given start and goal lanelet ids
// start pose and goal pose are set to the middle of the lanelet
LaneletRoute makeBehaviorRouteFromLaneId(const int & start_lane_id, const int & goal_lane_id)
LaneletRoute makeBehaviorRouteFromLaneId(
const int & start_lane_id, const int & goal_lane_id,
const std::string & package_name = "autoware_test_utils",
const std::string & map_filename = "lanelet2_map.osm")
{
LaneletRoute route;
route.header.frame_id = "map";
auto start_pose = createPoseFromLaneID(start_lane_id);
auto goal_pose = createPoseFromLaneID(goal_lane_id);
auto start_pose = createPoseFromLaneID(start_lane_id, package_name, map_filename);
auto goal_pose = createPoseFromLaneID(goal_lane_id, package_name, map_filename);
route.start_pose = start_pose;
route.goal_pose = goal_pose;

auto map_bin_msg = autoware::test_utils::makeMapBinMsg();
auto map_bin_msg = autoware::test_utils::makeMapBinMsg(package_name, map_filename);
// create route_handler
auto route_handler = std::make_shared<RouteHandler>();
route_handler->setMap(map_bin_msg);
Expand Down

0 comments on commit 41ca768

Please sign in to comment.