hand_control/src/filtre.cpp

116 lines
2.7 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-05-07 15:44:25 +00:00
#include <pcl/tracking/impl/hsv_color_coherence.hpp>
#include <assert.h>
2015-05-06 17:44:31 +00:00
2015-04-22 11:33:11 +00:00
2015-04-30 16:00:41 +00:00
typedef pcl::PointXYZRGB Point;
typedef pcl::PointCloud<Point> 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)
{
PointCloud::Ptr pcl(new PointCloud());
2015-04-30 16:00:41 +00:00
copy_info(msg, pcl);
BOOST_FOREACH (const Point& pt, msg->points)
2015-04-30 15:23:17 +00:00
{
2015-05-07 15:44:25 +00:00
if (pt.z < zmax and hue_dist(pt) < delta_hue)
2015-04-30 16:00:41 +00:00
pcl->push_back(pt);
2015-04-30 15:23:17 +00:00
}
2015-04-30 20:46:46 +00:00
pcl->height = 1;
pcl->width = pcl->points.size();
2015-04-22 19:38:54 +00:00
publisher.publish(pcl);
}
2015-05-07 15:44:25 +00:00
Callback(ros::Publisher& pub, float z, float h, float delta_h)
: publisher(pub), zmax(z), hue(h), delta_hue(delta_h)
{
assert(delta_hue > 0);
assert(zmax > 0);
assert(hue >= 0);
assert(hue <= 360.);
}
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-05-07 15:44:25 +00:00
float zmax, hue, delta_hue;
2015-04-30 16:00:41 +00:00
inline
void
copy_info(const PointCloud::ConstPtr& a,
PointCloud::Ptr b)
{
b->header = a->header;
b->sensor_origin_ = a->sensor_origin_;
b->sensor_orientation_ = a->sensor_orientation_;
b->is_dense = a->is_dense;
}
2015-05-07 15:44:25 +00:00
inline
float
hue_dist(const Point& pt)
{
float h, s, v, diff1, diff2;
pcl::tracking::RGB2HSV(pt.r, pt.g, pt.b, h, s, v);
h *= 360.0f ;
diff1 = std::fabs(h - hue);
if (h < hue)
diff2 = std::fabs(360.0f + h - hue);
else
diff2 = std::fabs(360.0f + hue - h);
return std::max(diff1, diff2);
}
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);
}
2015-05-07 15:44:25 +00:00
double hue(0);
if (node.getParam("hue", hue))
{
ROS_INFO("hue : %f" , hue);
} else {
node.setParam("hue", 0.0);
node.getParam("hue", hue);
ROS_INFO("hue : %f (default value)", hue);
}
double delta_hue(0);
if (node.getParam("delta_hue", delta_hue))
{
ROS_INFO("delta_hue : %f" , delta_hue);
} else {
node.setParam("delta_hue", 10.0);
node.getParam("delta_hue", delta_hue);
ROS_INFO("delta_hue : %f (default value)", delta_hue);
}
2015-04-30 15:30:53 +00:00
// initialisatio
2015-04-23 10:29:04 +00:00
ros::Publisher publisher = node.advertise<PointCloud>("output", 1);
2015-05-07 15:44:25 +00:00
Callback callback(publisher, (float) zmax, (float) hue, (float) delta_hue);
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
}