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-23 13:41:37 +00:00
|
|
|
#include <dynamic_reconfigure/server.h>
|
|
|
|
#include <hand_control/FiltreConfig.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
|
2015-05-23 13:41:37 +00:00
|
|
|
callback(const PointCloud::ConstPtr& msg)
|
2015-04-22 19:38:54 +00:00
|
|
|
{
|
|
|
|
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-23 13:05:17 +00:00
|
|
|
if (pt.z < z_max and hue_dist(pt) < delta_hue and sat(pt) < sat_max and sat(pt) > sat_min and val(pt) < val_max and val(pt) > val_min)
|
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-26 13:52:30 +00:00
|
|
|
Callback(const ros::Publisher& pub)
|
2015-05-23 13:41:37 +00:00
|
|
|
: publisher(pub), z_max(90.), hue(0.), delta_hue(20.), sat_min(0.3), sat_max(1.), val_min(0.3), val_max(1.)
|
2015-05-07 15:44:25 +00:00
|
|
|
{
|
|
|
|
assert(delta_hue > 0);
|
2015-05-23 13:05:17 +00:00
|
|
|
assert(z_max > 0);
|
2015-05-07 15:44:25 +00:00
|
|
|
assert(hue >= 0);
|
|
|
|
assert(hue <= 360.);
|
2015-05-22 15:39:33 +00:00
|
|
|
assert(sat_min >= 0);
|
|
|
|
assert(sat_max <= 1.);
|
|
|
|
assert(val_min >= 0);
|
|
|
|
assert(val_max <= 1.);
|
2015-05-07 15:44:25 +00:00
|
|
|
}
|
2015-04-22 16:31:16 +00:00
|
|
|
|
2015-05-23 13:41:37 +00:00
|
|
|
void
|
2015-05-26 13:52:30 +00:00
|
|
|
reconfigure(const hand_control::FiltreConfig& c, const uint32_t level) {
|
2015-05-23 13:41:37 +00:00
|
|
|
z_max = c.z_max;
|
|
|
|
hue = c.hue;
|
|
|
|
delta_hue = c.delta_hue;
|
|
|
|
val_min = c.val_min;
|
|
|
|
val_max = c.val_max;
|
|
|
|
sat_min = c.sat_min;
|
|
|
|
sat_max = c.sat_max;
|
|
|
|
}
|
|
|
|
|
2015-04-22 12:02:53 +00:00
|
|
|
private:
|
2015-04-22 14:53:52 +00:00
|
|
|
ros::Publisher publisher;
|
2015-05-23 13:05:17 +00:00
|
|
|
float z_max, hue, delta_hue, val_min, val_max, sat_min, sat_max;
|
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);
|
2015-05-07 15:49:25 +00:00
|
|
|
return std::min(diff1, diff2);
|
2015-05-07 15:44:25 +00:00
|
|
|
}
|
2015-05-26 13:52:30 +00:00
|
|
|
|
|
|
|
inline
|
|
|
|
float
|
|
|
|
sat(const Point& pt)
|
2015-05-22 15:09:35 +00:00
|
|
|
{
|
|
|
|
float h, s, v, diff1, diff2;
|
|
|
|
pcl::tracking::RGB2HSV(pt.r, pt.g, pt.b, h, s, v);
|
2015-05-22 15:33:50 +00:00
|
|
|
return s;
|
2015-05-22 15:09:35 +00:00
|
|
|
}
|
|
|
|
|
2015-05-26 13:52:30 +00:00
|
|
|
inline
|
|
|
|
float
|
|
|
|
val(const Point& pt)
|
2015-05-22 15:09:35 +00:00
|
|
|
{
|
|
|
|
float h, s, v, diff1, diff2;
|
|
|
|
pcl::tracking::RGB2HSV(pt.r, pt.g, pt.b, h, s, v);
|
2015-05-22 15:33:50 +00:00
|
|
|
return v;
|
2015-05-22 15:09:35 +00:00
|
|
|
}
|
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
|
|
|
|
2015-05-23 13:41:37 +00:00
|
|
|
// initialisation
|
2015-04-23 10:29:04 +00:00
|
|
|
ros::Publisher publisher = node.advertise<PointCloud>("output", 1);
|
2015-05-23 13:41:37 +00:00
|
|
|
Callback my_callback(publisher);
|
|
|
|
ros::Subscriber subscriber = node.subscribe<PointCloud>("input", 1, &Callback::callback, &my_callback);
|
|
|
|
|
|
|
|
dynamic_reconfigure::Server<hand_control::FiltreConfig> server;
|
|
|
|
dynamic_reconfigure::Server<hand_control::FiltreConfig>::CallbackType f;
|
|
|
|
f = boost::bind(&Callback::reconfigure, &my_callback, _1, _2);
|
|
|
|
server.setCallback(f);
|
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
|
|
|
}
|