hand_control/src/filtre.cpp

68 lines
1.6 KiB
C++
Raw Normal View History

2015-04-22 11:33:11 +00:00
#include <ros/ros.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_types.h>
2015-04-22 19:38:54 +00:00
#include <pcl/filters/passthrough.h>
2015-04-22 11:33:11 +00:00
2015-04-22 15:22:16 +00:00
typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
2015-04-22 12:02:53 +00:00
2015-04-22 14:53:52 +00:00
class Callback {
2015-04-22 11:33:11 +00:00
public:
2015-04-22 19:38:54 +00:00
void
operator()(const PointCloud::ConstPtr& msg)
{
ROS_INFO("PointCloud received");
// pour publier un shared_ptr (mieux)
PointCloud::Ptr pcl(new PointCloud());
// copie du nuage de point
*pcl = *msg;
// filtrage
double zmax(0.);
2015-04-23 15:56:13 +00:00
ros::param::getCached("/filtre/zmax", zmax);
2015-04-22 20:23:26 +00:00
ROS_INFO("zmax : %f", zmax);
2015-04-22 19:38:54 +00:00
z_filtre.setFilterLimits(0.0, zmax);
z_filtre.setInputCloud(pcl);
z_filtre.filter(*pcl);
// publication
publisher.publish(pcl);
ROS_INFO("PointCloud published");
}
Callback(ros::Publisher& pub) : publisher(pub), z_filtre()
{
z_filtre.setFilterFieldName("z");
}
2015-04-22 16:31:16 +00:00
2015-04-22 12:02:53 +00:00
private:
2015-04-22 14:53:52 +00:00
ros::Publisher publisher;
2015-04-22 19:38:54 +00:00
pcl::PassThrough<pcl::PointXYZRGB> z_filtre;
2015-04-22 11:33:11 +00:00
};
2015-04-22 19:38:54 +00:00
int
main(int argc, char** argv)
2015-04-22 11:33:11 +00:00
{
2015-04-22 12:02:53 +00:00
ros::init(argc, argv, "filtre");
2015-04-23 10:29:04 +00:00
ros::NodeHandle node("filtre");
2015-04-22 19:38:54 +00:00
// récupération des paramètres
double zmax(0);
if (node.getParam("zmax", zmax))
{
ROS_INFO("zmax : %f" , zmax);
} else {
node.setParam("zmax", 50.0);
node.getParam("zmax", zmax);
ROS_INFO("zmax : %f (default value)", zmax);
}
// initialisation
2015-04-23 10:29:04 +00:00
ros::Publisher publisher = node.advertise<PointCloud>("output", 1);
2015-04-22 16:31:16 +00:00
Callback callback(publisher);
2015-04-23 10:29:04 +00:00
ros::Subscriber subscriber = node.subscribe<PointCloud>("input", 1, callback);
2015-04-22 19:38:54 +00:00
// démarrage
2015-04-22 16:31:16 +00:00
ROS_INFO("node started");
2015-04-22 12:02:53 +00:00
ros::spin();
2015-04-22 16:31:16 +00:00
ROS_INFO("exit");
2015-04-22 12:02:53 +00:00
return 0;
2015-04-22 11:33:11 +00:00
}