|
38 | 38 | /*
|
39 | 39 | * Author: Sofie Nilsson
|
40 | 40 | */
|
41 |
| - |
| 41 | + |
42 | 42 |
|
43 | 43 | #include <pointcloud_to_laserscan/roi_outlier_removal.h>
|
44 | 44 | #include <pluginlib/class_list_macros.h>
|
@@ -118,7 +118,7 @@ void RoiOutlierRemovalNodelet::cloudCb(const sensor_msgs::PointCloud2ConstPtr &c
|
118 | 118 | // does not do anything if the problem dies not occur -> leave for compatibility
|
119 | 119 | std::string cloud_frame_id = cloud_msg->header.frame_id;
|
120 | 120 | if(cloud_frame_id.find_first_of("/") == 0)
|
121 |
| - { |
| 121 | + { |
122 | 122 | cloud_frame_id.erase(0,1);
|
123 | 123 | }
|
124 | 124 |
|
@@ -178,13 +178,13 @@ void RoiOutlierRemovalNodelet::cloudCb(const sensor_msgs::PointCloud2ConstPtr &c
|
178 | 178 |
|
179 | 179 | NODELET_DEBUG_STREAM("Transform and publish finished");
|
180 | 180 | }
|
181 |
| - |
| 181 | + |
182 | 182 | /**
|
183 | 183 | * Function to find the points within the defined region of interest and add those to the reduced_cloud.
|
184 | 184 | * The borders given in specified fame is transformed to the pc frame to avoid unnessecaric point transformations.
|
185 | 185 | * The reduced cloud in in the same frame as the original cloud, no transformation included!
|
186 | 186 | */
|
187 |
| -void RoiOutlierRemovalNodelet::reduce_point_cloud_to_roi(const pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_cloud, |
| 187 | +void RoiOutlierRemovalNodelet::reduce_point_cloud_to_roi(const pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_cloud, |
188 | 188 | pcl::PointCloud<pcl::PointXYZ>::Ptr reduced_pcl_cloud,
|
189 | 189 | const tf2::Transform &T)
|
190 | 190 | {
|
@@ -218,7 +218,7 @@ void RoiOutlierRemovalNodelet::reduce_point_cloud_to_roi(const pcl::PointCloud<p
|
218 | 218 | std::vector<int> indices;
|
219 | 219 | pcl::removeNaNFromPointCloud(*pcl_cloud,*pcl_cloud, indices);
|
220 | 220 | indices.clear();
|
221 |
| - |
| 221 | + |
222 | 222 | int n_points = pcl_cloud->size();
|
223 | 223 |
|
224 | 224 | // Declare help variables for point selection
|
@@ -287,4 +287,4 @@ void RoiOutlierRemovalNodelet::reduce_point_cloud_to_roi(const pcl::PointCloud<p
|
287 | 287 | }
|
288 | 288 | }
|
289 | 289 |
|
290 |
| -PLUGINLIB_DECLARE_CLASS(roi_outlier_removal, RoiOutlierRemovalNodelet, pointcloud_to_laserscan::RoiOutlierRemovalNodelet, nodelet::Nodelet); |
| 290 | +PLUGINLIB_EXPORT_CLASS(pointcloud_to_laserscan::RoiOutlierRemovalNodelet, nodelet::Nodelet); |
0 commit comments