26 #include <dynamic_reconfigure/server.h> 
   27 #include <pcl/filters/filter.h> 
   28 #include <pcl/point_cloud.h> 
   29 #include <pcl/point_types.h> 
   30 #include <pcl/segmentation/sac_segmentation.h> 
   32 #include <pcl_msgs/ModelCoefficients.h> 
   33 #include <pcl_msgs/PointIndices.h> 
   35 #include <sensor_msgs/PointCloud2.h> 
   36 #include <velo2cam_calibration/PlaneConfig.h> 
   50   dynamic_reconfigure::Server<velo2cam_calibration::PlaneConfig> 
server;
 
   51   dynamic_reconfigure::Server<velo2cam_calibration::PlaneConfig>::CallbackType
 
   60     std::vector<double> axis_param;
 
   61     Axis = Eigen::Vector3f::Zero();
 
   65     if (axis_param.size() == 3) {
 
   66       for (
int i = 0; i < 3; ++i) {
 
   67         Axis[i] = axis_param[i];
 
   82       ROS_INFO(
"Searching for planes perpendicular to %f %f %f", 
Axis[0],
 
   96     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(
 
   97         new pcl::PointCloud<pcl::PointXYZ>());
 
  100     pcl::ModelCoefficients::Ptr coefficients(
new pcl::ModelCoefficients);
 
  101     pcl::PointIndices::Ptr inliers(
new pcl::PointIndices);
 
  103     pcl::SACSegmentation<pcl::PointXYZ> seg;
 
  106                          ? pcl::SACMODEL_PARALLEL_PLANE
 
  107                          : pcl::SACMODEL_PERPENDICULAR_PLANE);
 
  109     seg.setMethodType(pcl::SAC_RANSAC);
 
  111     seg.setOptimizeCoefficients(
true);
 
  114     seg.setMaxIterations(250);
 
  116     std::vector<int> indices;
 
  117     pcl::removeNaNFromPointCloud(*cloud, *cloud, indices);
 
  119     seg.setInputCloud(cloud->makeShared());
 
  120     seg.segment(*inliers, *coefficients);
 
  122     if (inliers->indices.size() == 0) {
 
  123       ROS_WARN(
"Could not estimate a planar model for the given dataset.");
 
  127     pcl_msgs::PointIndices p_ind;
 
  130     p_ind.header = input->header;
 
  132     pcl_msgs::ModelCoefficients m_coeff;
 
  135     m_coeff.header = input->header;
 
  148 int main(
int argc, 
char **argv) {
 
  149   ros::init(argc, argv, 
"plane_segmentation");