hand_control/src/filter.cpp

125 lines
3.7 KiB
C++
Raw Normal View History

2015-09-18 14:52:52 +00:00
/* Copyright © 2015 CentraleSupélec
*
* This file is part of Hand Control.
*
* Hand Control is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Hand Control is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Hand Control. If not, see <http://www.gnu.org/licenses/>.
2015-08-21 18:39:01 +00:00
*/
2015-09-18 14:52:52 +00:00
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>
#include <dynamic_reconfigure/server.h>
#include <hand_control/FilterConfig.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
callback(const PointCloud::ConstPtr& msg)
2015-06-26 18:40:20 +00:00
// handles and filters the received PointCloud and
// publishes the filtered PointCloud
2015-04-22 19:38:54 +00:00
{
PointCloud::Ptr pcl(new PointCloud());
2015-06-26 18:40:20 +00:00
copy_info(msg, pcl); // copy the header
2015-04-30 16:00:41 +00:00
BOOST_FOREACH (const Point& pt, msg->points)
2015-04-30 15:23:17 +00:00
{
float hue_dist, sat, val;
hdist_s_v(pt, hue_dist, sat, val);
if (pt.z < z_max and hue_dist < delta_hue and sat < sat_max and sat > sat_min and val < val_max and val > 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);
}
Callback(const ros::Publisher& pub)
: 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-28 20:07:32 +00:00
{}
2015-04-22 16:31:16 +00:00
void
2015-06-26 18:40:20 +00:00
reconfigure(const hand_control::FilterConfig& c, const uint32_t& level)
// updates the parameters
{
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)
2015-06-26 18:40:20 +00:00
// copy the header info (useful in order to use rviz)
2015-04-30 16:00:41 +00:00
{
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
void
hdist_s_v(const Point& pt, float& h_dist, float& s, float& v)
2015-06-26 18:40:20 +00:00
// calculate the distance from the wished hue, the saturation and the value
// of the point
2015-05-07 15:44:25 +00:00
{
float h, diff1, diff2;
2015-05-07 15:44:25 +00:00
pcl::tracking::RGB2HSV(pt.r, pt.g, pt.b, h, s, v);
h *= 360.0f ;
diff1 = std::fabs(h - hue);
2015-06-26 18:40:20 +00:00
// hue is periodic
2015-05-07 15:44:25 +00:00
if (h < hue)
diff2 = std::fabs(360.0f + h - hue);
else
diff2 = std::fabs(360.0f + hue - h);
h_dist = std::min(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
{
ros::init(argc, argv, "filter");
ros::NodeHandle node("filter");
2015-04-23 10:29:04 +00:00
ros::Publisher publisher = node.advertise<PointCloud>("output", 1);
Callback my_callback(publisher);
ros::Subscriber subscriber = node.subscribe<PointCloud>("input", 1, &Callback::callback, &my_callback);
2015-06-26 18:40:20 +00:00
// sets up dynamic_reconfigure
dynamic_reconfigure::Server<hand_control::FilterConfig> server;
dynamic_reconfigure::Server<hand_control::FilterConfig>::CallbackType f;
f = boost::bind(&Callback::reconfigure, &my_callback, _1, _2);
server.setCallback(f);
2015-04-22 19:38:54 +00:00
2015-06-26 18:40:20 +00:00
// begins working
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
}