#include // PCL specific includes #include #include #include #include #include #include #include #include #include #include #include #include // void printinfo() // { // std::cout<<"OK"<::Ptr cloud(new pcl::PointCloud); pcl::fromPCLPointCloud2(pcl_pc2,*cloud); //Processing pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients); pcl::PointIndices::Ptr inliers (new pcl::PointIndices); // Create the segmentation object pcl::SACSegmentation seg; // Optional seg.setOptimizeCoefficients (true); // Mandatory seg.setModelType (pcl::SACMODEL_PLANE); seg.setMethodType (pcl::SAC_RANSAC); seg.setDistanceThreshold (0.01); seg.setInputCloud (cloud); seg.segment (*inliers, *coefficients); //ROS_INFO_STREAM("Coeff : "<values[0]<<" / "<values[1]<<" / "<values[2]<<" / "<values[3]); //Créations de l'output pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); //Extraction du plan (inliners) // for (size_t i = 0; i < inliers->indices.size (); ++i) // { // pcl_output->points.push_back( cloud->points[inliers->indices[i]]); // } //Extraction de l'objet (outliners) //Attention bruit ! pcl::ExtractIndices extract; extract.setInputCloud(cloud); extract.setIndices(inliers); extract.setNegative(true); extract.filter(*pcl_output); //Calcul du centre // CentroidPoint centroid; // for (size_t i = 0; i < pcl_output->size (); ++i) // { // centroid.add(*pcl_output[i]); // } // pcl::PointXYZ c1; // centroid.get (c1); Eigen::Vector4f barycentre; pcl::compute3DCentroid(*pcl_output, barycentre); // geometry_msgs::PointStamped center_msg; rviz_interface::NamedPoint center_msg; center_msg.name = "6DOF"; // for (size_t i = 0; i < pcl_output->size (); ++i) // { // if( pcl_output->points[i].x) // center.point.x += pcl_output->points[i]._PointXYZ::data[0]; // center.point.y += pcl_output->points[i]._PointXYZ::data[1]; // center.point.z += pcl_output->points[i]._PointXYZ::data[2]; // ROS_INFO_STREAM("Center clioyf : "<points[i].x<<" / "<points[i].y<<" / "<points[i].z); // } // center.point.x = center.point.x/pcl_output->size (); // center.point.y = center.point.y/pcl_output->size (); // center.point.z = center.point.z/pcl_output->size (); center_msg.point.x = barycentre[0]; center_msg.point.y = barycentre[1]; center_msg.point.z = barycentre[2]; center_msg.header.frame_id = input->header.frame_id; // ROS_INFO_STREAM("Center clioyf : "<points[0]._PointXYZ::data[0]<<" / "<points[0]._PointXYZ::data[1]<<" / "<points[0]._PointXYZ::data[2]); // ROS_INFO_STREAM("barycentre : "<header.frame_id; // Publish the data. pub.publish (output); pubc.publish( center_msg); } int main (int argc, char** argv) { // Initialize ROS ros::init (argc, argv, "my_pcl_tutorial"); ros::NodeHandle nh; // Create a ROS subscriber for the input point cloud ros::Subscriber sub = nh.subscribe ("/camera/depth_registered/points", 1, cloud_cb); // Create a ROS publisher for the output point cloud pub = nh.advertise ("/plane_output", 1); // pubc = nh.advertise ("/object_center", 1); pubc = nh.advertise ("/object_center", 1); // printinfo(); // Spin ros::spin (); }