mirror of
https://github.com/6-robot/wpb_home.git
synced 2025-09-15 12:58:59 +08:00
update grab_server
This commit is contained in:
parent
77a3c3a045
commit
b6ea2504f7
@ -205,11 +205,11 @@ void ProcCloudCB(const sensor_msgs::PointCloud2 &input)
|
||||
pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
|
||||
pcl::SACSegmentation<pcl::PointXYZRGB> segmentation;
|
||||
segmentation.setInputCloud(cloud_source_ptr);
|
||||
segmentation.setModelType(pcl::SACMODEL_PLANE);
|
||||
segmentation.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
|
||||
segmentation.setMethodType(pcl::SAC_RANSAC);
|
||||
segmentation.setDistanceThreshold(0.005);
|
||||
segmentation.setOptimizeCoefficients(true);
|
||||
Eigen::Vector3f axis = Eigen::Vector3f(0.0,1.0,0.0);
|
||||
Eigen::Vector3f axis = Eigen::Vector3f(0.0,0.0,1.0);
|
||||
segmentation.setAxis(axis);
|
||||
segmentation.setEpsAngle( 10.0f * (M_PI/180.0f) );
|
||||
pcl::PointIndices::Ptr planeIndices(new pcl::PointIndices);
|
||||
|
||||
@ -153,11 +153,11 @@ void ProcCloudCB(const sensor_msgs::PointCloud2 &input)
|
||||
pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
|
||||
pcl::SACSegmentation<pcl::PointXYZRGB> segmentation;
|
||||
segmentation.setInputCloud(cloud_source_ptr);
|
||||
segmentation.setModelType(pcl::SACMODEL_PLANE);
|
||||
segmentation.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
|
||||
segmentation.setMethodType(pcl::SAC_RANSAC);
|
||||
segmentation.setDistanceThreshold(0.005);
|
||||
segmentation.setOptimizeCoefficients(true);
|
||||
Eigen::Vector3f axis = Eigen::Vector3f(0.0,1.0,0.0);
|
||||
Eigen::Vector3f axis = Eigen::Vector3f(0.0,0.0,1.0);
|
||||
segmentation.setAxis(axis);
|
||||
segmentation.setEpsAngle( 10.0f * (M_PI/180.0f) );
|
||||
pcl::PointIndices::Ptr planeIndices(new pcl::PointIndices);
|
||||
|
||||
@ -147,11 +147,11 @@ void ProcCloudCB(const sensor_msgs::PointCloud2 &input)
|
||||
pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
|
||||
pcl::SACSegmentation<pcl::PointXYZRGB> segmentation;
|
||||
segmentation.setInputCloud(cloud_source_ptr);
|
||||
segmentation.setModelType(pcl::SACMODEL_PLANE);
|
||||
segmentation.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
|
||||
segmentation.setMethodType(pcl::SAC_RANSAC);
|
||||
segmentation.setDistanceThreshold(0.005);
|
||||
segmentation.setOptimizeCoefficients(true);
|
||||
Eigen::Vector3f axis = Eigen::Vector3f(0.0,1.0,0.0);
|
||||
Eigen::Vector3f axis = Eigen::Vector3f(0.0,0.0,1.0);
|
||||
segmentation.setAxis(axis);
|
||||
segmentation.setEpsAngle( 10.0f * (M_PI/180.0f) );
|
||||
pcl::PointIndices::Ptr planeIndices(new pcl::PointIndices);
|
||||
|
||||
Loading…
Reference in New Issue
Block a user