Skip to content

Commit 771087a

Browse files
benmaidelfmessmer
authored andcommitted
replaced deprecated pluginlib export macro
1 parent 4e33280 commit 771087a

File tree

3 files changed

+14
-14
lines changed

3 files changed

+14
-14
lines changed

src/ipa_pointcloud_to_laserscan_nodelet.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,7 @@ void IpaPointCloudToLaserScanNodelet::cloudCb(const sensor_msgs::PointCloud2Cons
132132
// does not do anything if the problem dies not occur -> leave for compatibility
133133
std::string cloud_frame_id = cloud_msg->header.frame_id;
134134
if(cloud_frame_id.find_first_of("/") == 0)
135-
{
135+
{
136136
cloud_frame_id.erase(0,1);
137137
}
138138

@@ -205,15 +205,15 @@ void IpaPointCloudToLaserScanNodelet::cloudCb(const sensor_msgs::PointCloud2Cons
205205
NODELET_DEBUG_STREAM("Transform and publisch for scan took " << dur.toSec());
206206
}
207207

208-
/**
209-
* Function to project the pointcloud points within specified region to
208+
/**
209+
* Function to project the pointcloud points within specified region to
210210
* the laser scan frame and fill out the laserscan message with the relevant ranges
211211
* from the projection.
212-
* Theborders for the point selection is transformed into pointcloud frame in order
212+
* Theborders for the point selection is transformed into pointcloud frame in order
213213
* save time by avoiding unnessecairy point transformations
214214
*/
215-
void IpaPointCloudToLaserScanNodelet::convert_pointcloud_to_laserscan(const sensor_msgs::PointCloud2ConstPtr &cloud,
216-
sensor_msgs::LaserScan &output,
215+
void IpaPointCloudToLaserScanNodelet::convert_pointcloud_to_laserscan(const sensor_msgs::PointCloud2ConstPtr &cloud,
216+
sensor_msgs::LaserScan &output,
217217
const tf2::Transform &T, const double range_min )
218218
{
219219
// Transform borders and target plane to original coordinates (saved resources to not have to transform the whole point cloud)
@@ -308,4 +308,4 @@ void IpaPointCloudToLaserScanNodelet::convert_pointcloud_to_laserscan(const sens
308308
}
309309
}
310310

311-
PLUGINLIB_DECLARE_CLASS(ipa_pointcloud_to_laserscan, IpaPointCloudToLaserScanNodelet, pointcloud_to_laserscan::IpaPointCloudToLaserScanNodelet, nodelet::Nodelet);
311+
PLUGINLIB_EXPORT_CLASS(pointcloud_to_laserscan::IpaPointCloudToLaserScanNodelet, nodelet::Nodelet);

src/pointcloud_to_laserscan_nodelet.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -238,4 +238,4 @@ namespace pointcloud_to_laserscan
238238

239239
}
240240

241-
PLUGINLIB_DECLARE_CLASS(pointcloud_to_laserscan, PointCloudToLaserScanNodelet, pointcloud_to_laserscan::PointCloudToLaserScanNodelet, nodelet::Nodelet);
241+
PLUGINLIB_EXPORT_CLASS(pointcloud_to_laserscan::PointCloudToLaserScanNodelet, nodelet::Nodelet);

src/roi_outlier_removal_nodelet.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
/*
3939
* Author: Sofie Nilsson
4040
*/
41-
41+
4242

4343
#include <pointcloud_to_laserscan/roi_outlier_removal.h>
4444
#include <pluginlib/class_list_macros.h>
@@ -118,7 +118,7 @@ void RoiOutlierRemovalNodelet::cloudCb(const sensor_msgs::PointCloud2ConstPtr &c
118118
// does not do anything if the problem dies not occur -> leave for compatibility
119119
std::string cloud_frame_id = cloud_msg->header.frame_id;
120120
if(cloud_frame_id.find_first_of("/") == 0)
121-
{
121+
{
122122
cloud_frame_id.erase(0,1);
123123
}
124124

@@ -178,13 +178,13 @@ void RoiOutlierRemovalNodelet::cloudCb(const sensor_msgs::PointCloud2ConstPtr &c
178178

179179
NODELET_DEBUG_STREAM("Transform and publish finished");
180180
}
181-
181+
182182
/**
183183
* Function to find the points within the defined region of interest and add those to the reduced_cloud.
184184
* The borders given in specified fame is transformed to the pc frame to avoid unnessecaric point transformations.
185185
* The reduced cloud in in the same frame as the original cloud, no transformation included!
186186
*/
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,
188188
pcl::PointCloud<pcl::PointXYZ>::Ptr reduced_pcl_cloud,
189189
const tf2::Transform &T)
190190
{
@@ -218,7 +218,7 @@ void RoiOutlierRemovalNodelet::reduce_point_cloud_to_roi(const pcl::PointCloud<p
218218
std::vector<int> indices;
219219
pcl::removeNaNFromPointCloud(*pcl_cloud,*pcl_cloud, indices);
220220
indices.clear();
221-
221+
222222
int n_points = pcl_cloud->size();
223223

224224
// Declare help variables for point selection
@@ -287,4 +287,4 @@ void RoiOutlierRemovalNodelet::reduce_point_cloud_to_roi(const pcl::PointCloud<p
287287
}
288288
}
289289

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

Comments
 (0)