@@ -413,9 +413,6 @@ void OctomapServer::insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
413
413
return ;
414
414
}
415
415
416
- Eigen::Matrix4f sensor_to_world =
417
- tf2::transformToEigen (sensor_to_world_transform_stamped.transform ).matrix ().cast <float >();
418
-
419
416
// set up filter for height range, also removes NANs:
420
417
pcl::PassThrough<PCLPoint> pass_x;
421
418
pass_x.setFilterFieldName (" x" );
@@ -450,14 +447,8 @@ void OctomapServer::insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
450
447
" You need to set the base_frame_id or disable filter_ground." );
451
448
}
452
449
453
-
454
- Eigen::Matrix4f sensor_to_base =
455
- tf2::transformToEigen (sensor_to_base_transform_stamped.transform ).matrix ().cast <float >();
456
- Eigen::Matrix4f base_to_world =
457
- tf2::transformToEigen (base_to_world_transform_stamped.transform ).matrix ().cast <float >();
458
-
459
450
// transform pointcloud from sensor frame to fixed robot frame
460
- pcl ::transformPointCloud (pc, pc, sensor_to_base );
451
+ pcl_ros ::transformPointCloud (pc, pc, sensor_to_base_transform_stamped );
461
452
pass_x.setInputCloud (pc.makeShared ());
462
453
pass_x.filter (pc);
463
454
pass_y.setInputCloud (pc.makeShared ());
@@ -467,11 +458,11 @@ void OctomapServer::insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
467
458
filterGroundPlane (pc, pc_ground, pc_nonground);
468
459
469
460
// transform clouds to world frame for insertion
470
- pcl ::transformPointCloud (pc_ground, pc_ground, base_to_world );
471
- pcl ::transformPointCloud (pc_nonground, pc_nonground, base_to_world );
461
+ pcl_ros ::transformPointCloud (pc_ground, pc_ground, base_to_world_transform_stamped );
462
+ pcl_ros ::transformPointCloud (pc_nonground, pc_nonground, base_to_world_transform_stamped );
472
463
} else {
473
464
// directly transform to map frame:
474
- pcl ::transformPointCloud (pc, pc, sensor_to_world );
465
+ pcl_ros ::transformPointCloud (pc, pc, sensor_to_world_transform_stamped );
475
466
476
467
// just filter height range:
477
468
pass_x.setInputCloud (pc.makeShared ());
@@ -1110,7 +1101,7 @@ void OctomapServer::filterGroundPlane(
1110
1101
second_pass.setFilterLimits (-ground_filter_plane_distance_, ground_filter_plane_distance_);
1111
1102
second_pass.setInputCloud (pc.makeShared ());
1112
1103
second_pass.filter (ground);
1113
- second_pass.setFilterLimitsNegative (true );
1104
+ second_pass.setNegative (true );
1114
1105
second_pass.filter (nonground);
1115
1106
}
1116
1107
// debug:
0 commit comments