From da3c8128326d50c5d15072d6a539514ea249fdf5 Mon Sep 17 00:00:00 2001 From: Louis-Guillaume DUBOIS Date: Wed, 22 Apr 2015 18:31:16 +0200 Subject: [PATCH] meilleur squelette de filtre --- hand_control/src/filtre.cpp | 20 +++++++++++++------- hand_control/src/random_pcl_publisher.cpp | 0 2 files changed, 13 insertions(+), 7 deletions(-) create mode 100644 hand_control/src/random_pcl_publisher.cpp diff --git a/hand_control/src/filtre.cpp b/hand_control/src/filtre.cpp index ad6dc45..8529eee 100644 --- a/hand_control/src/filtre.cpp +++ b/hand_control/src/filtre.cpp @@ -8,15 +8,18 @@ class Callback { public: void operator()(const PointCloud::ConstPtr& msg) { + ROS_INFO("PointCloud received"); + // pour publier un shared_ptr (mieux) + PointCloud::Ptr pcl; // copie du nuage de point - PointCloud pcl = *msg; + *pcl = *msg; // TODO : ôter les mauvais points publisher.publish(pcl); + ROS_INFO("PointCloud published"); } - Callback(ros::NodeHandle& node) - { - publisher = node.advertise("output", 1); - } + + Callback(ros::Publisher& pub) : publisher(pub) {} + private: ros::Publisher publisher; }; @@ -25,8 +28,11 @@ int main(int argc, char** argv) { ros::init(argc, argv, "filtre"); ros::NodeHandle node; - Callback callback(node); - ros::Subscriber subscriber = node.subscribe("input", 1, callback); + ros::Publisher publisher = node.advertise("filtre_output", 1); + Callback callback(publisher); + ros::Subscriber subscriber = node.subscribe("filtre_input", 1, callback); + ROS_INFO("node started"); ros::spin(); + ROS_INFO("exit"); return 0; } diff --git a/hand_control/src/random_pcl_publisher.cpp b/hand_control/src/random_pcl_publisher.cpp new file mode 100644 index 0000000..e69de29