Skip to content

Commit 99e9f64

Browse files
authored
Merge pull request #126 from OctoMap/topic/fix-ros2-pcl
[ROS2] Fix deprecated PCL API: setFilterLimitsNegative -> setNegative
2 parents 72141b9 + 8829049 commit 99e9f64

File tree

2 files changed

+7
-25
lines changed

2 files changed

+7
-25
lines changed

.github/workflows/industrial_ci_build_and_test.yml

+2-11
Original file line numberDiff line numberDiff line change
@@ -6,20 +6,11 @@ jobs:
66
strategy:
77
matrix:
88
env:
9-
- {ROS_DISTRO: rolling}
10-
- {ROS_DISTRO: rolling, PRERELEASE: true}
9+
# - {ROS_DISTRO: rolling}
1110
- {ROS_DISTRO: humble, PRERELEASE: true}
1211
- {ROS_DISTRO: iron, PRERELEASE: true}
13-
# env:
14-
# CCACHE_DIR: /github/home/.ccache # Enable ccache
1512
runs-on: ubuntu-latest
1613
steps:
17-
- uses: actions/checkout@v3
18-
# # This step will fetch/store the directory used by ccache before/after the ci run
19-
# - uses: actions/cache@v3
20-
# with:
21-
# path: ${{ env.CCACHE_DIR }}
22-
# key: ccache-${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }}
23-
# Run industrial_ci
14+
- uses: actions/checkout@v4
2415
- uses: 'ros-industrial/industrial_ci@master'
2516
env: ${{ matrix.env }}

octomap_server/src/octomap_server.cpp

+5-14
Original file line numberDiff line numberDiff line change
@@ -413,9 +413,6 @@ void OctomapServer::insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
413413
return;
414414
}
415415

416-
Eigen::Matrix4f sensor_to_world =
417-
tf2::transformToEigen(sensor_to_world_transform_stamped.transform).matrix().cast<float>();
418-
419416
// set up filter for height range, also removes NANs:
420417
pcl::PassThrough<PCLPoint> pass_x;
421418
pass_x.setFilterFieldName("x");
@@ -450,14 +447,8 @@ void OctomapServer::insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
450447
"You need to set the base_frame_id or disable filter_ground.");
451448
}
452449

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-
459450
// 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);
461452
pass_x.setInputCloud(pc.makeShared());
462453
pass_x.filter(pc);
463454
pass_y.setInputCloud(pc.makeShared());
@@ -467,11 +458,11 @@ void OctomapServer::insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
467458
filterGroundPlane(pc, pc_ground, pc_nonground);
468459

469460
// 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);
472463
} else {
473464
// directly transform to map frame:
474-
pcl::transformPointCloud(pc, pc, sensor_to_world);
465+
pcl_ros::transformPointCloud(pc, pc, sensor_to_world_transform_stamped);
475466

476467
// just filter height range:
477468
pass_x.setInputCloud(pc.makeShared());
@@ -1110,7 +1101,7 @@ void OctomapServer::filterGroundPlane(
11101101
second_pass.setFilterLimits(-ground_filter_plane_distance_, ground_filter_plane_distance_);
11111102
second_pass.setInputCloud(pc.makeShared());
11121103
second_pass.filter(ground);
1113-
second_pass.setFilterLimitsNegative(true);
1104+
second_pass.setNegative(true);
11141105
second_pass.filter(nonground);
11151106
}
11161107
// debug:

0 commit comments

Comments
 (0)