Skip to content

Commit a444714

Browse files
committed
feat: apply centerline resolution in differential map loader
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
1 parent 29f314e commit a444714

File tree

3 files changed

+14
-5
lines changed

3 files changed

+14
-5
lines changed

Diff for: map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp

+10-2
Original file line numberDiff line numberDiff line change
@@ -27,10 +27,11 @@ namespace autoware::map_loader
2727
{
2828

2929
Lanelet2DifferentialLoaderModule::Lanelet2DifferentialLoaderModule(
30-
rclcpp::Node * node, const double & center_line_resolution)
30+
rclcpp::Node * node, const double & center_line_resolution, const bool & use_waypoints)
3131
: logger_(node->get_logger()),
3232
clock_(node->get_clock()),
33-
center_line_resolution_(center_line_resolution)
33+
center_line_resolution_(center_line_resolution),
34+
use_waypoints_(use_waypoints)
3435
{
3536
const auto metadata_adaptor = autoware::component_interface_utils::NodeAdaptor(node);
3637
metadata_adaptor.init_pub(pub_lanelet_map_meta_data_);
@@ -77,6 +78,13 @@ bool Lanelet2DifferentialLoaderModule::onServiceGetDifferentialLanelet2Map(
7778
utils::merge_lanelet2_maps(*map, *map_tmp);
7879
}
7980

81+
// overwrite centerline
82+
if (use_waypoints_) {
83+
lanelet::utils::overwriteLaneletsCenterlineWithWaypoints(map, center_line_resolution_, false);
84+
} else {
85+
lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution_, false);
86+
}
87+
8088
// create the map bin message
8189
const auto map_bin_msg = utils::create_map_bin_msg(map, lanelet2_paths[0], rclcpp::Clock().now());
8290

Diff for: map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ class Lanelet2DifferentialLoaderModule
5151
{
5252
public:
5353
explicit Lanelet2DifferentialLoaderModule(
54-
rclcpp::Node * node, const double & center_line_resolution);
54+
rclcpp::Node * node, const double & center_line_resolution, const bool & use_waypoints);
5555

5656
void setLaneletMapMetadata(
5757
const std::map<std::string, Lanelet2FileMetaData> & lanelet2_metadata_dict, const double x_res,
@@ -74,7 +74,7 @@ class Lanelet2DifferentialLoaderModule
7474
std::optional<autoware_map_msgs::msg::MapProjectorInfo> projector_info_;
7575

7676
double center_line_resolution_;
77-
77+
bool use_waypoints_;
7878
bool onServiceGetDifferentialLanelet2Map(
7979
GetDifferentialLanelet2Map::Request::SharedPtr req,
8080
GetDifferentialLanelet2Map::Response::SharedPtr res);

Diff for: map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,8 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
9999

100100
if (get_parameter("enable_differential_map_loading").as_bool()) {
101101
differential_loader_module_ = std::make_unique<Lanelet2DifferentialLoaderModule>(
102-
this, get_parameter("center_line_resolution").as_double());
102+
this, get_parameter("center_line_resolution").as_double(),
103+
get_parameter("use_waypoints").as_bool());
103104
}
104105
}
105106

0 commit comments

Comments
 (0)