affichage sortie filtre

This commit is contained in:
Louis-Guillaume DUBOIS 2015-04-22 22:23:26 +02:00
parent f59b124658
commit ba815f3abc
2 changed files with 13 additions and 1 deletions

View file

@ -18,12 +18,24 @@ class Callback {
// filtrage
double zmax(0.);
ros::param::getCached("zmax", zmax);
ROS_INFO("zmax : %f", zmax);
z_filtre.setFilterLimits(0.0, zmax);
z_filtre.setInputCloud(pcl);
z_filtre.filter(*pcl);
// publication
publisher.publish(pcl);
ROS_INFO("PointCloud published");
ROS_INFO("filtered cloud :");
for(int i = 0; i < pcl->points.size(); ++i)
{
ROS_INFO("\nx : %f\ny : %f\nz : %f\nr : %d\ng : %d\nb : %d",
pcl->points[i].x,
pcl->points[i].y,
pcl->points[i].z,
pcl->points[i].r,
pcl->points[i].g,
pcl->points[i].b);
}
}
Callback(ros::Publisher& pub) : publisher(pub), z_filtre()

View file

@ -14,7 +14,7 @@ class Generator
public:
Generator(int l) : length(l), cgen()
{
UGenerator::Parameters params(-100, 100,-1);
UGenerator::Parameters params(0, 900, -1);
cgen.setParameters(params);
}