35 #define BOOST_PARAMETER_MAX_ARITY 7 38 #include <geometry_msgs/PoseStamped.h> 39 #include <geometry_msgs/PointStamped.h> 48 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
49 pcl::PointCloud<pcl::PointXYZRGB>::Ptr result_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
52 std::vector<int> indices;
53 cloud->is_dense =
false;
54 pcl::removeNaNFromPointCloud(*cloud, *cloud, indices);
56 pcl::MovingLeastSquares<pcl::PointXYZRGB, pcl::PointXYZRGB> smoother;
63 typename pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (
new typename pcl::search::KdTree<pcl::PointXYZRGB> ());
64 smoother.setSearchMethod (tree);
65 smoother.setInputCloud (cloud);
66 smoother.process (*result_cloud);
68 sensor_msgs::PointCloud2 pointcloud2;
70 pointcloud2.header.frame_id = input->header.frame_id;
71 pointcloud2.header.stamp = input->header.stamp;
97 DiagnosticNodelet::onInit();
103 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
104 dynamic_reconfigure::Server<Config>::CallbackType
f =
106 srv_->setCallback(f);
107 pub_ =advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MovingLeastSquareSmoothing, nodelet::Nodelet)
ros::Subscriber sub_input_
void publish(const boost::shared_ptr< M > &message) const
virtual void configCallback(Config &config, uint32_t level)
MovingLeastSquareSmoothingConfig Config
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void unsubscribe()
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void smooth(const sensor_msgs::PointCloud2ConstPtr &input)