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 _lasers_to_pointcloud_alg_node_h_ 00026 #define _lasers_to_pointcloud_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "lasers_to_pointcloud_alg.h" 00030 00031 #include <tf/transform_listener.h> 00032 #include <laser_geometry/laser_geometry.h> 00033 #include <pcl/point_types.h> 00034 #include <pcl/point_cloud.h> 00035 #include <pcl_ros/point_cloud.h> 00036 #include <pcl/ros/conversions.h> 00037 00038 #include <pcl_ros/transforms.h> 00039 00040 // [publisher subscriber headers] 00041 #include <sensor_msgs/LaserScan.h> 00042 #include <sensor_msgs/PointCloud2.h> 00043 00044 // [service client headers] 00045 00046 // [action server client headers] 00047 00052 class LasersToPointcloudAlgNode : public algorithm_base::IriBaseAlgorithm<LasersToPointcloudAlgorithm> 00053 { 00054 private: 00055 laser_geometry::LaserProjection laser_projector_; 00056 tf::TransformListener tfl_; 00057 uint counter_; 00058 00059 // [publisher attributes] 00060 ros::Publisher cloud_publisher_; 00061 sensor_msgs::PointCloud2 PointCloud2_msg_; 00062 00063 // [subscriber attributes] 00064 ros::Subscriber scan2_subscriber_; 00065 void scan2_callback(const sensor_msgs::LaserScan::ConstPtr& msg); 00066 CMutex scan2_mutex_; 00067 bool new_scan2_; 00068 sensor_msgs::PointCloud2 cloud2_; 00069 00070 ros::Subscriber scan1_subscriber_; 00071 void scan1_callback(const sensor_msgs::LaserScan::ConstPtr& msg); 00072 CMutex scan1_mutex_; 00073 bool new_scan1_; 00074 sensor_msgs::PointCloud2 cloud1_; 00075 00076 // [service attributes] 00077 00078 // [client attributes] 00079 00080 // [action server attributes] 00081 00082 // [action client attributes] 00083 00084 public: 00091 LasersToPointcloudAlgNode(void); 00092 00099 ~LasersToPointcloudAlgNode(void); 00100 00101 protected: 00114 void mainNodeThread(void); 00115 00128 void node_config_update(Config &config, uint32_t level); 00129 00136 void addNodeDiagnostics(void); 00137 00138 // [diagnostic functions] 00139 00140 // [test functions] 00141 }; 00142 00143 #endif