try : better filtre ?

This commit is contained in:
Louis-Guillaume DUBOIS 2015-04-30 17:23:17 +02:00
parent 4431d551f1
commit 74386e1a9f

View file

@ -13,28 +13,24 @@ class Callback {
ROS_INFO("PointCloud received"); ROS_INFO("PointCloud received");
// pour publier un shared_ptr (mieux) // pour publier un shared_ptr (mieux)
PointCloud::Ptr pcl(new PointCloud()); PointCloud::Ptr pcl(new PointCloud());
// copie du nuage de point
*pcl = *msg;
// filtrage // filtrage
double zmax(0.); double zmax(0.);
ros::param::getCached("/filtre/zmax", zmax); ros::param::getCached("/filtre/zmax", zmax);
ROS_INFO("zmax : %f", zmax); ROS_INFO("zmax : %f", zmax);
z_filtre.setFilterLimits(0.0, zmax); for (int i = 0; i < msg->points.size(); ++i)
z_filtre.setInputCloud(pcl); {
z_filtre.filter(*pcl); if (msg->points[i].z > zmax)
pcl->points.push_back(msg->points[i]);
}
// publication // publication
publisher.publish(pcl); publisher.publish(pcl);
ROS_INFO("PointCloud published"); ROS_INFO("PointCloud published");
} }
Callback(ros::Publisher& pub) : publisher(pub), z_filtre() Callback(ros::Publisher& pub) : publisher(pub) {}
{
z_filtre.setFilterFieldName("z");
}
private: private:
ros::Publisher publisher; ros::Publisher publisher;
pcl::PassThrough<pcl::PointXYZRGB> z_filtre;
}; };
int int