Skip to content

Commit

Permalink
pcl::transformPointCloud -> pcl_ros::transformPointCloud
Browse files Browse the repository at this point in the history
  • Loading branch information
wxmerkt committed Apr 8, 2024
1 parent fb6ceb6 commit 8b5062d
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions octomap_server/src/octomap_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -457,7 +457,7 @@ void OctomapServer::insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
tf2::transformToEigen(base_to_world_transform_stamped.transform).matrix().cast<float>();

// transform pointcloud from sensor frame to fixed robot frame
pcl::transformPointCloud(pc, pc, sensor_to_base);
pcl_ros::transformPointCloud(pc, pc, sensor_to_base);
pass_x.setInputCloud(pc.makeShared());
pass_x.filter(pc);
pass_y.setInputCloud(pc.makeShared());
Expand All @@ -467,11 +467,11 @@ void OctomapServer::insertCloudCallback(const PointCloud2::ConstSharedPtr cloud)
filterGroundPlane(pc, pc_ground, pc_nonground);

// transform clouds to world frame for insertion
pcl::transformPointCloud(pc_ground, pc_ground, base_to_world);
pcl::transformPointCloud(pc_nonground, pc_nonground, base_to_world);
pcl_ros::transformPointCloud(pc_ground, pc_ground, base_to_world);
pcl_ros::transformPointCloud(pc_nonground, pc_nonground, base_to_world);
} else {
// directly transform to map frame:
pcl::transformPointCloud(pc, pc, sensor_to_world);
pcl_ros::transformPointCloud(pc, pc, sensor_to_world);

// just filter height range:
pass_x.setInputCloud(pc.makeShared());
Expand Down

0 comments on commit 8b5062d

Please sign in to comment.