@@ -30,14 +30,14 @@ autoware_map_msgs::msg::PointCloudMapMetaData create_metadata(
30
30
// assume that the map ID = map path (for now)
31
31
const std::string & map_id = ele.first ;
32
32
33
- autoware_map_msgs::msg::PointCloudMapCellMetaData cell_metadata ;
34
- cell_metadata .cell_id = map_id;
35
- cell_metadata .min_x = metadata.min .x ;
36
- cell_metadata .min_y = metadata.min .y ;
37
- cell_metadata .max_x = metadata.max .x ;
38
- cell_metadata .max_y = metadata.max .y ;
33
+ autoware_map_msgs::msg::PointCloudMapCellMetaDataWithID cell_metadata_with_id ;
34
+ cell_metadata_with_id .cell_id = map_id;
35
+ cell_metadata_with_id. metadata .min_x = metadata.min .x ;
36
+ cell_metadata_with_id. metadata .min_y = metadata.min .y ;
37
+ cell_metadata_with_id. metadata .max_x = metadata.max .x ;
38
+ cell_metadata_with_id. metadata .max_y = metadata.max .y ;
39
39
40
- metadata_msg.metadata_list .push_back (cell_metadata );
40
+ metadata_msg.metadata_list .push_back (cell_metadata_with_id );
41
41
}
42
42
43
43
return metadata_msg;
@@ -81,29 +81,29 @@ bool SelectedMapLoaderModule::on_service_get_selected_point_cloud_map(
81
81
const std::string & map_id = path;
82
82
PCDFileMetadata metadata = requested_selected_map_iterator->second ;
83
83
84
- autoware_map_msgs::msg::PointCloudMapCellWithMetaData pointcloud_map_cell =
85
- load_point_cloud_map_cell_with_metadata (path, map_id);
86
- pointcloud_map_cell .metadata .min_x = metadata.min .x ;
87
- pointcloud_map_cell .metadata .min_y = metadata.min .y ;
88
- pointcloud_map_cell .metadata .max_x = metadata.max .x ;
89
- pointcloud_map_cell .metadata .max_y = metadata.max .y ;
84
+ autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id =
85
+ load_point_cloud_map_cell_with_id (path, map_id);
86
+ pointcloud_map_cell_with_id .metadata .min_x = metadata.min .x ;
87
+ pointcloud_map_cell_with_id .metadata .min_y = metadata.min .y ;
88
+ pointcloud_map_cell_with_id .metadata .max_x = metadata.max .x ;
89
+ pointcloud_map_cell_with_id .metadata .max_y = metadata.max .y ;
90
90
91
- res->new_pointcloud_cells .push_back (pointcloud_map_cell );
91
+ res->new_pointcloud_with_ids .push_back (pointcloud_map_cell_with_id );
92
92
}
93
93
res->header .frame_id = " map" ;
94
94
return true ;
95
95
}
96
96
97
- autoware_map_msgs::msg::PointCloudMapCellWithMetaData
98
- SelectedMapLoaderModule::load_point_cloud_map_cell_with_metadata (
97
+ autoware_map_msgs::msg::PointCloudMapCellWithID
98
+ SelectedMapLoaderModule::load_point_cloud_map_cell_with_id (
99
99
const std::string & path, const std::string & map_id) const
100
100
{
101
101
sensor_msgs::msg::PointCloud2 pcd;
102
102
if (pcl::io::loadPCDFile (path, pcd) == -1 ) {
103
103
RCLCPP_ERROR_STREAM (logger_, " PCD load failed: " << path);
104
104
}
105
- autoware_map_msgs::msg::PointCloudMapCellWithMetaData pointcloud_map_cell ;
106
- pointcloud_map_cell .pointcloud = pcd;
107
- pointcloud_map_cell. metadata .cell_id = map_id;
108
- return pointcloud_map_cell ;
105
+ autoware_map_msgs::msg::PointCloudMapCellWithID pointcloud_map_cell_with_id ;
106
+ pointcloud_map_cell_with_id .pointcloud = pcd;
107
+ pointcloud_map_cell_with_id .cell_id = map_id;
108
+ return pointcloud_map_cell_with_id ;
109
109
}
0 commit comments