From 891c6471ac5f84ce1316922231ecd18f46bca84c Mon Sep 17 00:00:00 2001 From: Louis-Guillaume DUBOIS Date: Wed, 22 Apr 2015 14:02:53 +0200 Subject: [PATCH] test foncteur pour callback --- hand_control/src/filtre.cpp | 38 +++++++++++++++++++++---------------- 1 file changed, 22 insertions(+), 16 deletions(-) diff --git a/hand_control/src/filtre.cpp b/hand_control/src/filtre.cpp index 03f9f4b..fa014d1 100644 --- a/hand_control/src/filtre.cpp +++ b/hand_control/src/filtre.cpp @@ -2,26 +2,32 @@ #include #include -class Filtre { - private: - typedef pcl::PointCloud PointCloud; - ros::NodeHandle node; - ros::Subscriber sub; - void callback(PointCloud&); +typedef pcl::PointCloud PointCloud; + +class Callback +{ public: - Filtre() + operator()(const PointCloud::Ptr& msg) { - ros::init(argc, argv, "filtre"); - callback(PointCloud& msg) - { - - } - subscriber = node.subscribe("input", 1, callback); - ros::spin(); + pub.publish(*msg); } + + Callback(ros::NodeHandle& node) + { + pub = node.advertise("output", 1); + } + + private: + ros::Publisher pub; }; -int main(int argc, char **argv) +int +main(int argc, char **argv) { - Filtre f(); + ros::init(argc, argv, "filtre"); + ros::NodeHandle node; + Callback callback(node); + ros::Subscriber subscriber = node.subscribe("input", 1, callback); + ros::spin(); + return 0; }