File tree 2 files changed +5
-3
lines changed
launch/tier4_perception_launch
perception/ground_segmentation/src
2 files changed +5
-3
lines changed Original file line number Diff line number Diff line change 19
19
<exec_depend >detected_object_feature_remover</exec_depend >
20
20
<exec_depend >detected_object_validation</exec_depend >
21
21
<exec_depend >detection_by_tracker</exec_depend >
22
+ <exec_depend >elevation_map_loader</exec_depend >
22
23
<exec_depend >euclidean_cluster</exec_depend >
23
24
<exec_depend >ground_segmentation</exec_depend >
24
25
<exec_depend >image_projection_based_fusion</exec_depend >
Original file line number Diff line number Diff line change @@ -292,12 +292,13 @@ void RANSACGroundFilterComponent::filter(
292
292
no_ground_cloud_msg_ptr->header = input->header ;
293
293
no_ground_cloud_msg_ptr->fields = input->fields ;
294
294
no_ground_cloud_msg_ptr->point_step = point_step;
295
+ no_ground_cloud_msg_ptr->data .resize (input->data .size ());
295
296
size_t output_size = 0 ;
296
297
// use not downsampled pointcloud for extract pointcloud that higher than height threshold
297
298
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]);
301
302
const Eigen::Vector3d transformed_point = plane_affine.inverse () * Eigen::Vector3d (x, y, z);
302
303
if (std::abs (transformed_point.z ()) > height_threshold_) {
303
304
std::memcpy (
You can’t perform that action at this time.
0 commit comments