Skip to content

Commit 7c97a6b

Browse files
authored
fix(ground_segmentation): fix bug (#7771)
1 parent 335ed8b commit 7c97a6b

File tree

2 files changed

+5
-3
lines changed

2 files changed

+5
-3
lines changed

launch/tier4_perception_launch/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
<exec_depend>detected_object_feature_remover</exec_depend>
2020
<exec_depend>detected_object_validation</exec_depend>
2121
<exec_depend>detection_by_tracker</exec_depend>
22+
<exec_depend>elevation_map_loader</exec_depend>
2223
<exec_depend>euclidean_cluster</exec_depend>
2324
<exec_depend>ground_segmentation</exec_depend>
2425
<exec_depend>image_projection_based_fusion</exec_depend>

perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -292,12 +292,13 @@ void RANSACGroundFilterComponent::filter(
292292
no_ground_cloud_msg_ptr->header = input->header;
293293
no_ground_cloud_msg_ptr->fields = input->fields;
294294
no_ground_cloud_msg_ptr->point_step = point_step;
295+
no_ground_cloud_msg_ptr->data.resize(input->data.size());
295296
size_t output_size = 0;
296297
// use not downsampled pointcloud for extract pointcloud that higher than height threshold
297298
for (size_t global_size = 0; global_size < input->data.size(); global_size += point_step) {
298-
float x = *reinterpret_cast<float *>(input->data[global_size + x_offset]);
299-
float y = *reinterpret_cast<float *>(input->data[global_size + y_offset]);
300-
float z = *reinterpret_cast<float *>(input->data[global_size + z_offset]);
299+
float x = *reinterpret_cast<const float *>(&input->data[global_size + x_offset]);
300+
float y = *reinterpret_cast<const float *>(&input->data[global_size + y_offset]);
301+
float z = *reinterpret_cast<const float *>(&input->data[global_size + z_offset]);
301302
const Eigen::Vector3d transformed_point = plane_affine.inverse() * Eigen::Vector3d(x, y, z);
302303
if (std::abs(transformed_point.z()) > height_threshold_) {
303304
std::memcpy(

0 commit comments

Comments
 (0)