Skip to content

Commit e8d80c0

Browse files
StepTurtleMehmet Dogru
authored and
Mehmet Dogru
committed
Update msgs
Signed-off-by: Barış Zeren <bzeren1819@gmail.com>
1 parent 0b9d1f5 commit e8d80c0

File tree

2 files changed

+7
-9
lines changed

2 files changed

+7
-9
lines changed

map/autoware_dynamic_lanelet_provider/src/dynamic_lanelet_provider.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -77,9 +77,9 @@ DynamicLaneletProviderNode::DynamicLaneletProviderNode(const rclcpp::NodeOptions
7777
for (const auto & data : msg->metadata_list) {
7878
Lanelet2FileMetaData metadata;
7979
metadata.id = data.tile_id;
80-
metadata.origin_lat = data.metadata.origin_lat;
81-
metadata.origin_lon = data.metadata.origin_lon;
82-
metadata.mgrs_code = data.metadata.mgrs_code;
80+
metadata.origin_lat = data.origin_lat;
81+
metadata.origin_lon = data.origin_lon;
82+
metadata.mgrs_code = data.mgrs_code;
8383
lanelet_map_meta_data_list_.push_back(metadata);
8484
}
8585
});
@@ -144,7 +144,7 @@ void DynamicLaneletProviderNode::updateMap(const geometry_msgs::msg::Point & pos
144144
}
145145

146146
auto request = std::make_shared<autoware_map_msgs::srv::GetDifferentialLanelet2Map::Request>();
147-
request->osm_file_ids.insert(request->osm_file_ids.end(), cache_ids.begin(), cache_ids.end());
147+
request->vector_map_file_ids.insert(request->vector_map_file_ids.end(), cache_ids.begin(), cache_ids.end());
148148

149149
while (!map_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) {
150150
RCLCPP_INFO(get_logger(), "Waiting for lanelet loader service");

map/map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ bool Lanelet2DifferentialLoaderModule::differentialLanelet2Load(
6666
{
6767
// check osm ids
6868
std::vector<std::string> lanelet2_paths;
69-
for (const auto & id : request->osm_file_ids) {
69+
for (const auto & id : request->vector_map_file_ids) {
7070
auto it = std::find_if(
7171
lanelet2_file_metadata_dict_.begin(), lanelet2_file_metadata_dict_.end(),
7272
[&id](const auto & file) { return file.second.id == id; });
@@ -131,15 +131,13 @@ Lanelet2DifferentialLoaderModule::getLaneletMapMetaDataMsg() const
131131
autoware_map_msgs::msg::LaneletMapMetaData metadata;
132132
for (const auto & file : lanelet2_file_metadata_dict_) {
133133
autoware_map_msgs::msg::LaneletMapTileMetaData tile_msg;
134+
tile_msg.tile_id = file.second.id;
134135
tile_msg.mgrs_code = file.second.mgrs_code;
135136
tile_msg.origin_lat = file.second.origin_lat;
136137
tile_msg.origin_lon = file.second.origin_lon;
137138

138-
autoware_map_msgs::msg::LaneletMapTileMetaDataWithID tile_msg_with_id;
139-
tile_msg_with_id.metadata = tile_msg;
140-
tile_msg_with_id.tile_id = file.second.id;
141139

142-
metadata.metadata_list.push_back(tile_msg_with_id);
140+
metadata.metadata_list.push_back(tile_msg);
143141
}
144142
metadata.header.frame_id = "map";
145143
metadata.header.stamp = clock_->now();

0 commit comments

Comments
 (0)