00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author 00003 // All rights reserved. 00004 // 00005 // This file is part of iri-ros-pkg 00006 // iri-ros-pkg is free software: you can redistribute it and/or modify 00007 // it under the terms of the GNU Lesser General Public License as published by 00008 // the Free Software Foundation, either version 3 of the License, or 00009 // at your option) any later version. 00010 // 00011 // This program is distributed in the hope that it will be useful, 00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 // GNU Lesser General Public License for more details. 00015 // 00016 // You should have received a copy of the GNU Lesser General Public License 00017 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00018 // 00019 // IMPORTANT NOTE: This code has been generated through a script from the 00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness 00021 // of the scripts. ROS topics can be easly add by using those scripts. Please 00022 // refer to the IRI wiki page for more information: 00023 // http://wikiri.upc.es/index.php/Robotics_Lab 00024 00025 #ifndef _average_point_cloud_alg_node_h_ 00026 #define _average_point_cloud_alg_node_h_ 00027 00028 #include <boost/circular_buffer.hpp> 00029 00030 #include <iri_base_algorithm/iri_base_algorithm.h> 00031 #include "average_point_cloud_alg.h" 00032 00033 //#include <ros/ros.h> 00034 #include <pcl_ros/point_cloud.h> 00035 #include <pcl/point_types.h> 00036 #include <pcl/io/pcd_io.h> 00037 00038 // [publisher subscriber headers] 00039 #include <sensor_msgs/PointCloud2.h> 00040 00041 // [service client headers] 00042 00043 // [action server client headers] 00044 00045 typedef union { 00046 struct /*anonymous*/ 00047 { 00048 unsigned char Blue; 00049 unsigned char Green; 00050 unsigned char Red; 00051 unsigned char Alpha; 00052 }; 00053 float float_value; 00054 long long_value; 00055 } RGBValue; 00056 00057 //TODO: dynamically memory storage to be able to change this from dynamic_reconfigure 00058 //static const int iBuffer = 25; 00063 class AveragePointCloudAlgNode : public algorithm_base::IriBaseAlgorithm<AveragePointCloudAlgorithm> 00064 { 00065 private: 00066 // AMb això el que rebem es mapeja a un PCL::PointCloud!! --> + fàcil de manipular 00067 typedef pcl::PointXYZRGB Point; 00068 typedef pcl::PointCloud<Point> PointCloud; 00069 //boost::circular_buffer<PointCloud, Eigen::aligned_allocator<PointCloud> > cloudBuffer_; 00070 boost::circular_buffer<sensor_msgs::PointCloud2, Eigen::aligned_allocator<sensor_msgs::PointCloud2> > cloudBuffer_; 00071 00072 bool init_; // wait for the fisrt iBuffer images before start publishing 00073 int iBuffer_; // number of current pcls on the buffer 00074 int iCurrent_; // iterator in the pointcloud buffer 00075 00076 00077 // [publisher attributes] 00078 ros::Publisher pcl2_pub_; 00079 //PointCloud pcl2_final_msg_; 00080 //PointCloud pcl2_current_msg_; 00081 sensor_msgs::PointCloud2 pcl2_final_msg_; 00082 sensor_msgs::PointCloud2 pcl2_current_msg_; 00083 00084 // [subscriber attributes] 00085 ros::Subscriber pcl2_sub_; 00086 CMutex input_mutex_; 00087 00088 // [service attributes] 00089 00090 // [client attributes] 00091 00092 // [action server attributes] 00093 00094 // [action client attributes] 00095 00096 void input_callback(const sensor_msgs::PointCloud2ConstPtr& msg); 00097 00098 public: 00105 AveragePointCloudAlgNode(void); 00106 00113 ~AveragePointCloudAlgNode(void); 00114 00115 protected: 00128 void mainNodeThread(void); 00129 00142 void node_config_update(Config &config, uint32_t level); 00143 00150 void addNodeDiagnostics(void); 00151 00152 // [diagnostic functions] 00153 00154 // [test functions] 00155 }; 00156 00157 #endif