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 _obstacle_detection_normals_alg_node_h_ 00026 #define _obstacle_detection_normals_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "obstacle_detection_normals_alg.h" 00030 00031 #include <ros/ros.h> 00032 00033 #include <pcl_ros/point_cloud.h> 00034 #include <pcl/ros/conversions.h> 00035 #include <pcl/point_types.h> 00036 #include <pcl/filters/filter.h> 00037 00038 00039 // [publisher subscriber headers] 00040 #include <sensor_msgs/PointCloud2.h> 00041 #include <sensor_msgs/PointCloud.h> 00042 #include <sensor_msgs/point_cloud_conversion.h> 00043 // [service client headers] 00044 00045 // [action server client headers] 00046 00047 using namespace std; 00048 00049 00054 class ObstacleDetectionNormalsAlgNode : public algorithm_base::IriBaseAlgorithm<ObstacleDetectionNormalsAlgorithm> 00055 { 00056 private: 00057 00058 int KSearch; 00059 float normal_z,normal_y,normal_x,min_dist; 00060 00061 // [publisher attributes] 00062 ros::Publisher obstacles_publisher_; 00063 ros::Publisher all_rg_publisher_; 00064 sensor_msgs::PointCloud2 obstacles_msg_; 00065 sensor_msgs::PointCloud obstaclespc_msg_; 00066 sensor_msgs::PointCloud2 all_rg_msg_; 00067 00068 00069 00070 // [subscriber attributes] 00071 ros::Subscriber input_subscriber_; 00072 void input_callback(const sensor_msgs::PointCloud2::ConstPtr& msg); 00073 CMutex input_mutex_; 00074 00075 // [service attributes] 00076 00077 // [client attributes] 00078 00079 // [action server attributes] 00080 ObstacleDetectionNormalsAlgorithm obstacle_detect; 00081 // [action client attributes] 00082 00083 public: 00090 ObstacleDetectionNormalsAlgNode(void); 00091 00098 ~ObstacleDetectionNormalsAlgNode(void); 00099 00100 protected: 00113 void mainNodeThread(void); 00114 00127 void node_config_update(Config &config, uint32_t level); 00128 00135 void addNodeDiagnostics(void); 00136 00137 // [diagnostic functions] 00138 00139 // [test functions] 00140 00141 }; 00142 00143 #endif