diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml
index 6ec706a4aad32..57d4b209efeef 100644
--- a/launch/tier4_perception_launch/package.xml
+++ b/launch/tier4_perception_launch/package.xml
@@ -19,6 +19,7 @@
detected_object_feature_remover
detected_object_validation
detection_by_tracker
+ elevation_map_loader
euclidean_cluster
ground_segmentation
image_projection_based_fusion
diff --git a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp
index d7fa777dc58c9..aa224e7adc5bf 100644
--- a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp
+++ b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp
@@ -292,12 +292,13 @@ void RANSACGroundFilterComponent::filter(
no_ground_cloud_msg_ptr->header = input->header;
no_ground_cloud_msg_ptr->fields = input->fields;
no_ground_cloud_msg_ptr->point_step = point_step;
+ no_ground_cloud_msg_ptr->data.resize(input->data.size());
size_t output_size = 0;
// use not downsampled pointcloud for extract pointcloud that higher than height threshold
for (size_t global_size = 0; global_size < input->data.size(); global_size += point_step) {
- float x = *reinterpret_cast(input->data[global_size + x_offset]);
- float y = *reinterpret_cast(input->data[global_size + y_offset]);
- float z = *reinterpret_cast(input->data[global_size + z_offset]);
+ float x = *reinterpret_cast(&input->data[global_size + x_offset]);
+ float y = *reinterpret_cast(&input->data[global_size + y_offset]);
+ float z = *reinterpret_cast(&input->data[global_size + z_offset]);
const Eigen::Vector3d transformed_point = plane_affine.inverse() * Eigen::Vector3d(x, y, z);
if (std::abs(transformed_point.z()) > height_threshold_) {
std::memcpy(